diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..d034b58 --- /dev/null +++ b/.gitignore @@ -0,0 +1 @@ +Generated/* \ No newline at end of file diff --git a/create_bus_from_mavlink_header.m b/Functions/create_bus_from_mavlink_header.m similarity index 71% rename from create_bus_from_mavlink_header.m rename to Functions/create_bus_from_mavlink_header.m index f637a11..6d2e07a 100644 --- a/create_bus_from_mavlink_header.m +++ b/Functions/create_bus_from_mavlink_header.m @@ -1,12 +1,7 @@ function [busObj, bus_name, bus_orig_dtypes] = create_bus_from_mavlink_header(filename) -% CREATE_BUS_FROM_MAVLINK_HEADER: Create a Simulink Bus from a single -% MAVLink message header file -% -% NOTE: This function is called by another function create_sfun_header, -% so the user would typically not have to directly use this function. +% CREATE_BUS_FROM_MAVLINK_HEADER: Create a Simulink Bus from a MAVLink message header file % -% Input: string containing the MAVLink message header file name -% +% Input: string containing the header file name. % Output: % busObj: bus object % bus_name: string containing name of the bus @@ -19,14 +14,14 @@ fid = fopen(filename, 'r'); datatypes = readtable('datatype_map.csv','ReadVariableNames',1); -% Skip lines till "MAVPACKED" +% Assume that the first line containing "typedef struct __" is the message +% definition. lin = fgetl(fid); -while ~contains(lin,'MAVPACKED') +while ~startsWith(lin, 'typedef struct __') lin = fgetl(fid); end -% Next line is "typedef struct" - extract bus name from this -lin = fgetl(fid); +% Extract bus name bus_name = strtrim(erase(lin,{'typedef struct __','{'})); bus_orig_dtypes = struct; @@ -44,12 +39,13 @@ if isempty(dimensions) dimensions = 1; else + % DO NOT CHANGE the following to str2double dimensions = str2num(dimensions{1}); name = regexp(name,'\[(\d*)\]','split'); name = name{1}; end - idx = find(strcmp(datatype,datatypes.mavlink), 1); + idx = find(strcmp(datatype,datatypes.px4), 1); if isempty(idx) error(['Could not find datatype ' datatype ' in datatype_map.csv']) else @@ -59,7 +55,7 @@ busElements(nfields).DataType = char(datatypes.simulink(idx)); busElements(nfields).Dimensions = dimensions; busElements(nfields).Description = description; - bus_orig_dtypes.(name) = char(datatypes.mavlink(idx)); + bus_orig_dtypes.(name) = char(datatypes.px4(idx)); end lin = fgetl(fid); end diff --git a/create_sfun_decode.m b/Functions/create_sfun_decode.m similarity index 77% rename from create_sfun_decode.m rename to Functions/create_sfun_decode.m index f2e32f3..e78d2db 100644 --- a/create_sfun_decode.m +++ b/Functions/create_sfun_decode.m @@ -3,19 +3,10 @@ function create_sfun_decode(filenames, sys_id, comp_id) % messages from an incoming MAVLink stream % % Inputs: -% filenames: strings containing the full path to the MAVLink messages -% header file names. These files must be created as a part of a -% single MAVLink dialect, and must reside in the directory -% structure of the corresponding dialect. In other words, the -% directory containing this message file must also contain the -% "mavlink.h" file, and its parent directory must contain the -% other commond mavlink files such as "protocol.h". -% -% NOTE: To ensure compiler independence, provide the full paths -% of the message files, and not relative paths. -% -% sys_id: MAVLink SYSID to be used for Simulink (default 100) -% comp_id: MAVLink COMPID to be used for Simulink (default 200) +% filenames: cell array of strings containing the MAVLink message header +% files for messages to be decoded +% sys_id: MAVLink SYSID to be used for Simulink (default 100) +% comp_id: MAVLink COMPID to be used for Simulink (default 200) % % Output: % This function creates the Simulink buses, the s-function header files, @@ -24,20 +15,14 @@ function create_sfun_decode(filenames, sys_id, comp_id) %Part of the Simulink MAVLink package. %(c) Aditya Joshi, November 2017 - -%% Parse inputs - if ~iscell(filenames), filenames = {filenames}; end -disp('*** Running create_sfun_decode:') +disp('--') +disp('Creating decoder s-function:') if nargin < 2, sys_id = 100; end if nargin < 3, comp_id = 200; end -pathname = fileparts(mfilename('fullpath')); -sfun_include_dir = fullfile(pathname,'include'); -mavlink_dialect_dir = fileparts(filenames{1}); - %% Create message header files @@ -47,12 +32,13 @@ function create_sfun_decode(filenames, sys_id, comp_id) end -%% Create decode header file +%% Create header file -fprintf('Creating s-function header file... ') +fprintf('Writing the decoder s-function header file... ') -header_filename = fullfile(sfun_include_dir,'sfun_decode_mavlink.h'); -fid = fopen(header_filename,'w'); +header_filename = 'Generated/sfun_decode_mavlink.h'; + +fid = fopen(header_filename, 'w'); % Write header fprintf(fid,'%s\n','/*'); @@ -62,9 +48,9 @@ function create_sfun_decode(filenames, sys_id, comp_id) fprintf(fid,'%s\n','*/'); fprintf(fid,'%s\n',''); -% Include sfun headers +% Include message headers for i = 1:length(filenames) - fprintf(fid,'%s\n',['#include "' sfun_include_dir filesep 'sfun_mavlink_msg_' mavlink_msg_names{i} '.h"']); + fprintf(fid,'%s\n',['#include "sfun_mavlink_msg_' mavlink_msg_names{i} '.h"']); end % Define NFIELDS_OUTPUT_BUS @@ -120,8 +106,8 @@ function create_sfun_decode(filenames, sys_id, comp_id) %% Create cpp file -output_filename = 'sfun_decode_mavlink'; -fprintf(['Creating the output file ' output_filename '.cpp ... ']); +output_filename = 'Generated/sfun_decode_mavlink'; +fprintf(['Writing source file ' output_filename '.cpp ... ']); fin = fopen('sfun_decode_mavlink_template.cpp','r'); fout = fopen([output_filename '.cpp'],'w'); @@ -158,12 +144,13 @@ function create_sfun_decode(filenames, sys_id, comp_id) fprintf(fout,'%s\n',['#define COMP_ID ' num2str(comp_id)]); case 3 - % include mavlink common header - fprintf(fout,'%s\n',['#include "' mavlink_dialect_dir filesep 'mavlink.h"']); + % include mavlink.h file + mavlink_h = strcat(fileparts(filenames{1}), filesep, 'mavlink.h'); + fprintf(fout,'%s\n',['#include "' mavlink_h '"']); case 4 - % include header file - fprintf(fout,'%s\n',['#include "' header_filename '"']); + % include message header file + fprintf(fout,'%s\n', '#include "sfun_decode_mavlink.h"'); case 5 % configure output ports @@ -229,12 +216,9 @@ function create_sfun_decode(filenames, sys_id, comp_id) %% Compile cpp file disp('Compiling the s-function...') -eval(['mex ' output_filename '.cpp']); - -movefile([output_filename '.*'],'sfunctions'); -disp('S-function source and compiled files are in the folder ''sfunctions''') - -% Add the sfunctions directory to path -addpath(fullfile(pathname,'sfunctions')); +eval('cd Generated') +eval('mex sfun_decode_mavlink.cpp'); +eval('cd ..') -disp('***') \ No newline at end of file +disp('Finished, compiled s-function is in the folder ''Generated''') +disp('--') \ No newline at end of file diff --git a/create_sfun_encode.m b/Functions/create_sfun_encode.m similarity index 59% rename from create_sfun_encode.m rename to Functions/create_sfun_encode.m index 0851e49..64cfd57 100644 --- a/create_sfun_encode.m +++ b/Functions/create_sfun_encode.m @@ -3,19 +3,9 @@ function create_sfun_encode(filename, sys_id, comp_id) % message % % Inputs: -% filename: string containing the full path to the MAVLink message -% header file name. This file must be created as a part of a -% MAVLink dialect, and must reside in the directory structure -% of the corresponding dialect. In other words, the directory -% containing this message file must also contain the -% "mavlink.h" file, and its parent directory must contain the -% other commond mavlink files such as "protocol.h". -% -% NOTE: To ensure compiler independence, provide the full path -% of the message file, and not relative path. -% -% sys_id: MAVLink SYSID to be used for Simulink (default 100) -% comp_id: MAVLink COMPID to be used for Simulink (default 200) +% filename: string containing the MAVLink message header file +% sys_id: MAVLink SYSID to be used for Simulink (default 100) +% comp_id: MAVLink COMPID to be used for Simulink (default 200) % % Output: % This function creates the Simulink bus, the s-function header file, the @@ -25,27 +15,21 @@ function create_sfun_encode(filename, sys_id, comp_id) %(c) Aditya Joshi, November 2017 -%% Parse inputs +%% Create header file + +disp('--') +disp(['Creating encoder s-function for ' filename ':']) if nargin < 2, sys_id = 100; end if nargin < 3, comp_id = 200; end - -pathname = fileparts(mfilename('fullpath')); -sfun_include_dir = fullfile(pathname,'include'); -mavlink_dialect_dir = fileparts(filename); - - -%% Create header file - -disp(' ') -disp(['*** Running create_sfun_encode for ' filename ':']) + mavlink_msg_name = create_sfun_header(filename); %% Create cpp file -output_filename = ['sfun_encode_msg_' mavlink_msg_name]; -fprintf(['Creating the output file ' output_filename '.cpp ... ']); +output_filename = ['Generated/sfun_encode_msg_' mavlink_msg_name]; +fprintf(['Writing source file ' output_filename '.cpp ... ']); fin = fopen('sfun_encode_msg_template.cpp','r'); fout = fopen([output_filename '.cpp'],'w'); @@ -83,24 +67,22 @@ function create_sfun_encode(filename, sys_id, comp_id) fprintf(fout,'%s\n',['#define COMP_ID ' num2str(comp_id)]); case 4 - fprintf(fout,'%s\n',['#include "' mavlink_dialect_dir filesep 'mavlink.h"']); + mavlink_h = strcat(fileparts(filename), filesep, 'mavlink.h'); + fprintf(fout,'%s\n',['#include "' mavlink_h '"']); case 5 - fprintf(fout,'%s\n',['#include "' sfun_include_dir filesep 'sfun_mavlink_msg_' mavlink_msg_name '.h"']); + fprintf(fout,'%s\n',['#include "sfun_mavlink_msg_' mavlink_msg_name '.h"']); case 6 fprintf(fout,'\t%s\n',['ssRegisterTypeFromNamedObject(S, BUS_NAME_' upper(mavlink_msg_name) ', &BusType);']); - + case 7 - fprintf(fout,'\t%s\n',['ssSetOutputPortWidth(S, 0, ENCODED_LEN_' upper(mavlink_msg_name) ');']); - - case 8 fprintf(fout,'\t%s\n',['int_T *busInfo = (int_T *) malloc(2*NFIELDS_BUS_' upper(mavlink_msg_name) '*sizeof(int_T));']); - case 9 + case 8 fprintf(fout,'\t%s\n',['encode_businfo_' mavlink_msg_name '(S, busInfo, 0);']); - case 10 + case 9 fprintf(fout,'\t%s\n',['encode_vector_' mavlink_msg_name '(uvec, busInfo, yvec, 0);']); end @@ -119,13 +101,11 @@ function create_sfun_encode(filename, sys_id, comp_id) %% Compile cpp file disp('Compiling the s-function...') +eval('cd Generated') +output_filename = ['sfun_encode_msg_' mavlink_msg_name]; eval(['mex ' output_filename '.cpp']); +eval('cd ..') -movefile([output_filename '.*'],'sfunctions'); -disp('S-function source and compiled files are in the folder ''sfunctions''') - -% Add the sfunctions directory to path -addpath(fullfile(pathname,'sfunctions')); - -disp('***') +disp('Finished, compiled s-function is in the folder ''Generated''') +disp('--') diff --git a/create_sfun_header.m b/Functions/create_sfun_header.m similarity index 79% rename from create_sfun_header.m rename to Functions/create_sfun_header.m index 5004cef..cf0b441 100644 --- a/create_sfun_header.m +++ b/Functions/create_sfun_header.m @@ -1,56 +1,38 @@ function mavlink_msg_name = create_sfun_header(filename) -% CREATE_SFUN_HEADER: Create the message header files to be included in the -% s-functions used in the Simulink MAVLink library -% -% NOTE: This function is called by other functions create_sfun_encode and -% create_sfun_decode, so the user would typically not have to -% directly use this function. +% CREATE_SFUN_HEADER: Create the message header files for s-functions in Simulink MAVLink % % Inputs: -% filename: string containing the full path to the MAVLink message -% header file name. This file must be created as a part of a -% MAVLink dialect, and must reside in the directory structure -% of the corresponding dialect. In other words, the directory -% containing this message file must also contain the -% "mavlink.h" file, and its parent directory must contain the -% other commond mavlink files such as "protocol.h". -% NOTE: To ensure compiler independence, provide the full path -% of the message file, and not relative path. +% mavlink_msg_name: string containing the name of the mavlink message. In the +% standard naming convention, everythin after the "mavlink_msg_" +% in the name of the mavlink header file is considered the +% message name. e.g. if the header file is "mavlink_msg_altitude", +% the message name is "altitude". +% simulink_bus: the Simulink bus object corresponding to this message. This bus +% is created by the function "create_bus_from_mavlink_header" % -% Output: The function creates the .h header file in the "include" -% directory of the Simulink MAVLink library. +% Output: the function creates the .h header file in the "include" directory. % %Part of the Simulink MAVLink package. %(c) Aditya Joshi, October 2017 -%% Parse inputs - -pathname = fileparts(mfilename('fullpath')); - - %% Create and save bus -disp('**') - fprintf('Creating Simulink bus from message... '); [simulink_bus, simulink_bus_name, bus_orig_dtypes] = create_bus_from_mavlink_header(filename); assignin('base',simulink_bus_name,simulink_bus); -disp('done'); + eval([simulink_bus_name '= simulink_bus;']) -busfilename = ['buses/bus_' simulink_bus_name '.mat']; +busfilename = ['Generated/bus_' simulink_bus_name '.mat']; save(busfilename,simulink_bus_name); -disp(['Bus is saved in ' busfilename]); - -% Add the buses directory to path -addpath(fullfile(pathname,'buses')); +disp(['done, bus is saved in ' busfilename]); %% Prepare header file -fprintf('Creating the s-function header file... '); +fprintf('Writing the message s-function header file... '); mavlink_msg_name = erase(simulink_bus_name,{'mavlink_','_t'}); -fileName = fullfile(pathname,'include',['sfun_mavlink_msg_' mavlink_msg_name '.h']); +fileName = ['Generated/sfun_mavlink_msg_' mavlink_msg_name '.h']; fid = fopen(fileName,'w'); @@ -65,7 +47,6 @@ % Use full path in the #include statements fprintf(fid,'%s\n',''); fprintf(fid,'%s\n',['#include "' filename '"']); -fprintf(fid,'%s\n',''); fprintf(fid,'%s\n',['#define BUS_NAME_' upper(mavlink_msg_name) ' "' simulink_bus_name '"']); fprintf(fid,'%s\n',['#define NFIELDS_BUS_' upper(mavlink_msg_name) ' ' num2str(length(simulink_bus.Elements))]); fprintf(fid,'%s\n',['#define ENCODED_LEN_' upper(mavlink_msg_name) ' (MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_' upper(mavlink_msg_name) '_LEN)']); @@ -198,7 +179,5 @@ fclose(fid); -disp('done'); -disp(['Header file is saved in ' fileName]); +disp(['done, header file is saved in ' fileName]); -disp('**') diff --git a/datatype_map.csv b/Functions/datatype_map.csv similarity index 82% rename from datatype_map.csv rename to Functions/datatype_map.csv index 3c893b2..6c10ac7 100644 --- a/datatype_map.csv +++ b/Functions/datatype_map.csv @@ -1,4 +1,4 @@ -mavlink,simulink +px4,simulink uint8_t,uint8 int8_t,int8 uint16_t,uint16 diff --git a/README.md b/README.md index 8790df8..e272fd3 100644 --- a/README.md +++ b/README.md @@ -1,40 +1,58 @@ -# Simulink-MAVLink v2.0 +# Simulink-MAVLink **MAVLink communication support for Simulink** ![Encode Image](https://raw.githubusercontent.com/aditya00j/simulink_mavlink/master/images/example_encode.PNG) ![Decode Image](https://raw.githubusercontent.com/aditya00j/simulink_mavlink/master/images/example_decode.PNG) ___ -## What is Simulink-MAVLink? +## What is Simulink-MAVLink? + * [MAVLink] library essentially serializes structured messages into uint8 vectors (bit streams). * Encoding a MAVLink message means taking structured data and packing it into a bit stream. * Decoding an incoming MAVLink bit stream means storing the uint8 data into a memory buffer, and extracting the desired messages into their structures. - * Simulink already has capabilities to send and receive bit streams on communication channels such as UDP and serial. + * Simulink already has capabilities to send and receive bit streams on communication channels such as TCP/UDP and UART. * Simulink also has a way of representing structured numerical data - Simulink Bus. * Therefore, this small and light-weight Simulink-MAVLink library was built to provide Simulink S-functions utilizing the MAVLink library, which facilitate two-way data conversion: Simulink Bus to uint8, and uint8 to Simulink Bus. This library was built and tested on Matlab R2017a. [MAVLink]: https://github.com/mavlink/mavlink - - ## How to get started? - 1. Get MAVLink header files for any dialect (e.g. "common", provided by default with this library). - 2. Identify the messages that you wish to send or receive. - 3. For each message, run the Matlab function "create_sfun_encode" provided in this library. It will create and save a Simulink bus for this message, create the header and source files for the s-function, and finally compile the s-function. **Note that you have to load the bus into your workspace when you use this s-function in Simulink.** - 4. For decoding particular messages from an incoming MAVLink stream, run the Matlab function "create_sfun_decode". This will create and save Simulink buses for all the messages you selected, create the headers and source file for the s-function, and finally compile the s-function. - 5. Use the compiles s-functions in Simulink. - - See the "examples" folder for an example of this process. - - - ## Following general principles were used in formulating this library: - 1. Do not recreate any functionality that already exists either in Simulink or MAVLink - only build the absolute minimum bridges required in the interface. This ensures wide applicability and inter-operability. - 2. Make the interfaces as explicit as possible. This puts the onus of ensuring correct datatypes and other run-time issues on the user, instead of having to cater for non-standard conditions in this library. - 3. Provide only the two-way data conversion capability, and nothing else. - - - ## Notes - * **Terms of Use:** I created this library for my personal use. I've tried to make it abstract in its formation, but it may or may not suit your needs. There are other excellent implementations for Matlab-MAVLink interface online which you can use. They didn't suit my needs exactly, so I wrote this small library. I am releasing it here for common good, without assuming any responsibility of its accuracy or future support. And like all open source software, you are agreeing to these terms by using this library. It's extremely unlikely that your computer will burst into flames by using this library, but nothing's impossible! - * **Combining messages:** Logically, you need to write one s-function for encoding each message. The bit streams for all these messages can be combined using standard Simulink blocks like "Byte Pack" or a simple Mux, before sending them over a communication channel. This follows from Principle 1 above. On the other hand, during decoding, you have only one bit stream per MAVLink channel. It means you can have only 1 s-function for decoding all messages. This process is shown in the example included. - * **Why Buses?:** For most MAVLink messages, you can simply use a vector of the type "double", which is the standard Simulink signal. However, following Principle 2 above, the s-function should not make any (incorrect) assumptions about the data types. Therefore, the best way to ensure that the user correctly packs and unpacks a MAVLink message is to provide a transparent interface. A Simulink Bus is the best way to do that. It might seem like a chore to uses buses for simple messages, but in general it's better. Plus, since the bus objects are automatically created from the MAVLink headers, they are explicitly guaranteed to be compatible. Another advantage is that the meta-data related to the message elements is also extracted into the bus, which can be used for a quick reference in Simulink. - * **Unsupported data types:** Simulink does not support "uint64" data type. This is used in many MAVLink messages for logging time. The fields of this type are typecast as "double" in the bus object. This hasn't given me any errors until now, since typecasting between "uint64" and "double" works in most cases. But you should be aware of this difference, as theoretically there are some uint64 integers that cannot be stored in double. Also, some MAVLink messages have character arrays storing non-numerical data. Obviously, this cannot be used directly in Simulink, so they are typecast into "uint8". In Simulink, you can convert the characters into uint8 before passing them to the s-function (e.g. "uint8('HELLO')"). The data type conversion between MAVLink struct and Simulink Bus is defined in the file "datatype_map.csv". + +## Getting Started + +### Create Message Busses and S-Functions + +1. Use the script `setup.m` to choose which MAVLink messages need to be encoded/decoded for your application. +2. Running the script will create the message busses, write the header and source files for the message encoder and decoder functions, and finally compile the s-functions using the `mex` command. Assuming all the options are specified correctly and the mex compilation is working, the compiled S-functions are created in the `Generated` folder. + +For each message to be encoded, a separate S-function is created, that accepts the message bus as input, and creates a uint8 array of length `MAVLINK_MAX_PACKET_LEN` (= 280 for MAVLink v2.0). On the other hand, for decoding the received MAVLink data, there is only a single S-function, which accepts a uint8 array of length `MAVLINK_MAX_PACKET_LEN`, and decodess it into individual message busses. + + +### Use S-Functions in Simulink to Test Local Encoding/Decoding + +To verify that the encoding/decoding works correctly, open the Simulink model `Examples\test_attitude.slx`. This model simply packs arbitrary data into the Attitude message bus. Run the model and verify that the data in busses `sent_bus` and `recd_bus` matches. + +Note the following points while running the model: + +* All the message busses (`mavlink_attitude_t` in this case) must be loaded into the base workspace before running the model. +* The signal on the input port of an encoder S-function must be a non-virtual bus, and all the individual signal types for the bus input must be set correctly. + +### Use S-Functions in Simulink to Exchange MAVLink Data on TCP + +The Simulink model `Examples\test_attitude_tcp.slx` shows how the bit streams can be sent/received over TCP to communicate with PX4 Autopilot. Example of sending and receiving data over TCP/IP in Simulink is explained [here](https://www.mathworks.com/help/instrument/send-and-receive-data-over-a-tcpip-network.html). Once you've started an echo server on port 4560 in Matlab, you can run the Simulink model and verify that the data in busses `msg_sent` and `msg_recd` matches. + + +## General Principles +Following general principles were used in formulating this library: + +1. Do not recreate any functionality that already exists either in Simulink or MAVLink - only build the absolute minimum bridges required in the interface. This ensures wide applicability and inter-operability. +2. Make the interfaces as explicit as possible. This puts the onus of ensuring correct datatypes and other run-time issues on the user, instead of having to cater for non-standard conditions in this library. +3. Provide only the two-way data conversion capability, and nothing else. + + +## Notes +* **Combining messages:** Logically, you need to write one S-function for encoding each message. The bit streams for all these messages can be combined using standard Simulink blocks like "Byte Pack" or a simple Mux, before sending them over a communication channel. On the other hand, during decoding, you have only one bit stream per MAVLink channel. It means you can have only 1 S-function for decoding all messages. This process is shown in the example included. + +* **Why Busses?:** For most MAVLink messages, you can simply use a vector of the type "double", which is the standard Simulink signal. However, following Principle 2 above, the s-function should not make any (incorrect) assumptions about the data types. Therefore, the best way to ensure that the user correctly packs and unpacks a MAVLink message is to provide a transparent interface. A Simulink Bus is the best way to do that. It might seem like a chore to uses buses for simple messages, but in general it's better. Plus, since the bus objects are automatically created from the MAVLink headers, they are explicitly guaranteed to be compatible. Another advantage is that the meta-data related to the message elements is also extracted into the bus, which can be used for a quick reference in Simulink. + +* **Unsupported data types:** Simulink does not support "uint64" data type. This is used in many MAVLink messages for logging time. The fields of this type are typecast as "double" in the bus object. This hasn't given me any errors until now, since typecasting between "uint64" and "double" works in most cases. But you should be aware of this difference, as theoretically there are some uint64 integers that cannot be stored in double. Also, some MAVLink messages have character arrays storing non-numerical data. Obviously, this cannot be used directly in Simulink, so they are typecast into "uint8". In Simulink, you can convert the characters into uint8 before passing them to the s-function (e.g. "uint8('HELLO')"). The data type conversion between MAVLink struct and Simulink Bus is defined in the file "datatype_map.csv". diff --git a/sfun_decode_mavlink_template.cpp b/Templates/sfun_decode_mavlink_template.cpp similarity index 95% rename from sfun_decode_mavlink_template.cpp rename to Templates/sfun_decode_mavlink_template.cpp index 460beca..fcb4f25 100644 --- a/sfun_decode_mavlink_template.cpp +++ b/Templates/sfun_decode_mavlink_template.cpp @@ -16,7 +16,7 @@ <1> // #define SYS_ID 100 <2> // #define COMP_ID 200 -<3> //#include "include/mavlink/v1.0/common/mavlink.h" +<3> // #include "include/mavlink/v1.0/common/mavlink.h" <4> // include sfunc_decode_mavlink.h diff --git a/sfun_encode_msg_template.cpp b/Templates/sfun_encode_msg_template.cpp similarity index 92% rename from sfun_encode_msg_template.cpp rename to Templates/sfun_encode_msg_template.cpp index 973bc4b..6d7e4cf 100644 --- a/sfun_encode_msg_template.cpp +++ b/Templates/sfun_encode_msg_template.cpp @@ -49,7 +49,7 @@ static void mdlInitializeSizes(SimStruct *S) if (!ssSetNumOutputPorts(S, 1)) return; -<7> // ssSetOutputPortWidth(S, 0, OUTPUT_VECTOR_LEN); + ssSetOutputPortWidth(S, 0, MAVLINK_MAX_PACKET_LEN); ssSetOutputPortDataType(S, 0, SS_UINT8); ssSetNumSampleTimes(S, 1); @@ -87,12 +87,12 @@ static void mdlInitializeSampleTimes(SimStruct *S) #define MDL_START static void mdlStart(SimStruct *S) { -<8> // int_T *busInfo = (int_T *) malloc(2*NFIELDS_INPUT_BUS*sizeof(int_T)); +<7> // int_T *busInfo = (int_T *) malloc(2*NFIELDS_INPUT_BUS*sizeof(int_T)); if(busInfo == NULL) { ssSetErrorStatus(S, "Memory allocation failure"); return; } -<9> // encode_input_businfo(S, busInfo); +<8> // encode_input_businfo(S, busInfo); } /* end mdlStart */ @@ -108,7 +108,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) const char *uvec = (const char *) ssGetInputPortSignal(S, 0); uint8_T *yvec = (uint8_T *) ssGetOutputPortSignal(S, 0); int_T* busInfo = (int_T *) ssGetUserData(S); -<10> // encode_output_vector(uvec, busInfo, yvec); +<9> // encode_output_vector(uvec, busInfo, yvec); } /* Function: mdlTerminate ====================================================== diff --git a/buses/bus_mavlink_attitude_t.mat b/buses/bus_mavlink_attitude_t.mat deleted file mode 100644 index bd8c2b9..0000000 Binary files a/buses/bus_mavlink_attitude_t.mat and /dev/null differ diff --git a/buses/bus_mavlink_raw_imu_t.mat b/buses/bus_mavlink_raw_imu_t.mat deleted file mode 100644 index 50c02de..0000000 Binary files a/buses/bus_mavlink_raw_imu_t.mat and /dev/null differ diff --git a/examples/example_create_sfunctions.m b/examples/example_create_sfunctions.m deleted file mode 100644 index 2d2cda0..0000000 --- a/examples/example_create_sfunctions.m +++ /dev/null @@ -1,35 +0,0 @@ -% Example for creating s-functions for encoding as well as decoding -% MAVLink messages - -% See "examples_use_sfunctions.slx" for usage of these s-functions in -% Simulink - -% Go to the top directory -this_dir = fileparts(mfilename('fullpath')); -dir_sep = regexp(this_dir, filesep, 'split'); -cd(fullfile(dir_sep{1:end-1})); - -% Select the MAVLink header files for messages we want to use -filenames = { - 'D:\simulink_mavlink\include\mavlink\v1.0\common\mavlink_msg_heartbeat.h'; - 'D:\simulink_mavlink\include\mavlink\v1.0\common\mavlink_msg_attitude.h'; - 'D:\simulink_mavlink\include\mavlink\v1.0\common\mavlink_msg_raw_imu.h'; - }; - - -%% Create encoder s-functions -% Calling create_sfun_encode will creates buses, header files, s-function -% cpp files, and will finally compile them. This will create one encoder -% s-function for each message - -for i = 1:length(filenames) - create_sfun_encode(filenames{i}); -end - - -%% Create decider s-function -% Calling create_sfun_decode will creates buses, header files, s-function -% cpp file, and will finally compile it. This will create one decoder -% s-function in total - -create_sfun_decode(filenames); diff --git a/examples/example_use_sfunctions.slx b/examples/example_use_sfunctions.slx deleted file mode 100644 index 3ad485f..0000000 Binary files a/examples/example_use_sfunctions.slx and /dev/null differ diff --git a/examples/test_attitude.slx b/examples/test_attitude.slx new file mode 100644 index 0000000..d83bcad Binary files /dev/null and b/examples/test_attitude.slx differ diff --git a/examples/test_attitude_tcp.slx b/examples/test_attitude_tcp.slx new file mode 100644 index 0000000..5fbf07c Binary files /dev/null and b/examples/test_attitude_tcp.slx differ diff --git a/include/mavlink/v1.0/checksum.h b/include/mavlink/v1.0/checksum.h deleted file mode 100644 index 0f30b65..0000000 --- a/include/mavlink/v1.0/checksum.h +++ /dev/null @@ -1,96 +0,0 @@ -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef _CHECKSUM_H_ -#define _CHECKSUM_H_ - -// Visual Studio versions before 2010 don't have stdint.h, so we just error out. -#if (defined _MSC_VER) && (_MSC_VER < 1600) -#error "The C-MAVLink implementation requires Visual Studio 2010 or greater" -#endif - -#include - -/** - * - * CALCULATE THE CHECKSUM - * - */ - -#define X25_INIT_CRC 0xffff -#define X25_VALIDATE_CRC 0xf0b8 - -#ifndef HAVE_CRC_ACCUMULATE -/** - * @brief Accumulate the X.25 CRC by adding one char at a time. - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new char to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) -{ - /*Accumulate one byte of data into the CRC*/ - uint8_t tmp; - - tmp = data ^ (uint8_t)(*crcAccum &0xff); - tmp ^= (tmp<<4); - *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); -} -#endif - - -/** - * @brief Initiliaze the buffer for the X.25 CRC - * - * @param crcAccum the 16 bit X.25 CRC - */ -static inline void crc_init(uint16_t* crcAccum) -{ - *crcAccum = X25_INIT_CRC; -} - - -/** - * @brief Calculates the X.25 checksum on a byte buffer - * - * @param pBuffer buffer containing the byte array to hash - * @param length length of the byte array - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) -{ - uint16_t crcTmp; - crc_init(&crcTmp); - while (length--) { - crc_accumulate(*pBuffer++, &crcTmp); - } - return crcTmp; -} - - -/** - * @brief Accumulate the X.25 CRC by adding an array of bytes - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new bytes to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length) -{ - const uint8_t *p = (const uint8_t *)pBuffer; - while (length--) { - crc_accumulate(*p++, crcAccum); - } -} - -#endif /* _CHECKSUM_H_ */ - -#ifdef __cplusplus -} -#endif diff --git a/include/mavlink/v1.0/common/common.h b/include/mavlink/v1.0/common/common.h deleted file mode 100644 index 6fe88a6..0000000 --- a/include/mavlink/v1.0/common/common.h +++ /dev/null @@ -1,1170 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from common.xml - * @see http://mavlink.org - */ -#pragma once -#ifndef MAVLINK_COMMON_H -#define MAVLINK_COMMON_H - -#ifndef MAVLINK_H - #error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. -#endif - -#undef MAVLINK_THIS_XML_IDX -#define MAVLINK_THIS_XML_IDX 1 - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 4, 0, 0, 27, 25, 0, 0, 0, 0, 0, 72, 26, 181, 225, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 81, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 12, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 22, 13, 255, 14, 18, 43, 8, 22, 14, 36, 43, 41, 32, 243, 14, 93, 0, 100, 36, 60, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 40, 63, 182, 40, 0, 0, 0, 0, 0, 0, 32, 52, 53, 6, 2, 38, 19, 254, 36, 30, 18, 18, 51, 9, 0} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 196, 0, 0, 15, 3, 0, 0, 0, 0, 0, 167, 183, 119, 191, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 47, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 174, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 47, 72, 131, 127, 0, 103, 154, 178, 200, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 163, 105, 151, 35, 150, 0, 0, 0, 0, 0, 0, 90, 104, 85, 95, 130, 184, 81, 8, 204, 49, 170, 44, 83, 46, 0} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_COMMON - -// ENUM DEFINITIONS - - -/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */ -#ifndef HAVE_ENUM_MAV_AUTOPILOT -#define HAVE_ENUM_MAV_AUTOPILOT -typedef enum MAV_AUTOPILOT -{ - MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */ - MAV_AUTOPILOT_RESERVED=1, /* Reserved for future use. | */ - MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */ - MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */ - MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */ - MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */ - MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */ - MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */ - MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */ - MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */ - MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */ - MAV_AUTOPILOT_FP=11, /* FlexiPilot | */ - MAV_AUTOPILOT_PX4=12, /* PX4 Autopilot - http://pixhawk.ethz.ch/px4/ | */ - MAV_AUTOPILOT_SMACCMPILOT=13, /* SMACCMPilot - http://smaccmpilot.org | */ - MAV_AUTOPILOT_AUTOQUAD=14, /* AutoQuad -- http://autoquad.org | */ - MAV_AUTOPILOT_ARMAZILA=15, /* Armazila -- http://armazila.com | */ - MAV_AUTOPILOT_AEROB=16, /* Aerob -- http://aerob.ru | */ - MAV_AUTOPILOT_ASLUAV=17, /* ASLUAV autopilot -- http://www.asl.ethz.ch | */ - MAV_AUTOPILOT_SMARTAP=18, /* SmartAP Autopilot - http://sky-drones.com | */ - MAV_AUTOPILOT_ENUM_END=19, /* | */ -} MAV_AUTOPILOT; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_TYPE -#define HAVE_ENUM_MAV_TYPE -typedef enum MAV_TYPE -{ - MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */ - MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ - MAV_TYPE_QUADROTOR=2, /* Quadrotor | */ - MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */ - MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */ - MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */ - MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */ - MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */ - MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */ - MAV_TYPE_ROCKET=9, /* Rocket | */ - MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */ - MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */ - MAV_TYPE_SUBMARINE=12, /* Submarine | */ - MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */ - MAV_TYPE_OCTOROTOR=14, /* Octorotor | */ - MAV_TYPE_TRICOPTER=15, /* Tricopter | */ - MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */ - MAV_TYPE_KITE=17, /* Kite | */ - MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */ - MAV_TYPE_VTOL_DUOROTOR=19, /* Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. | */ - MAV_TYPE_VTOL_QUADROTOR=20, /* Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. | */ - MAV_TYPE_VTOL_TILTROTOR=21, /* Tiltrotor VTOL | */ - MAV_TYPE_VTOL_RESERVED2=22, /* VTOL reserved 2 | */ - MAV_TYPE_VTOL_RESERVED3=23, /* VTOL reserved 3 | */ - MAV_TYPE_VTOL_RESERVED4=24, /* VTOL reserved 4 | */ - MAV_TYPE_VTOL_RESERVED5=25, /* VTOL reserved 5 | */ - MAV_TYPE_GIMBAL=26, /* Onboard gimbal | */ - MAV_TYPE_ADSB=27, /* Onboard ADSB peripheral | */ - MAV_TYPE_ENUM_END=28, /* | */ -} MAV_TYPE; -#endif - -/** @brief These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. */ -#ifndef HAVE_ENUM_FIRMWARE_VERSION_TYPE -#define HAVE_ENUM_FIRMWARE_VERSION_TYPE -typedef enum FIRMWARE_VERSION_TYPE -{ - FIRMWARE_VERSION_TYPE_DEV=0, /* development release | */ - FIRMWARE_VERSION_TYPE_ALPHA=64, /* alpha release | */ - FIRMWARE_VERSION_TYPE_BETA=128, /* beta release | */ - FIRMWARE_VERSION_TYPE_RC=192, /* release candidate | */ - FIRMWARE_VERSION_TYPE_OFFICIAL=255, /* official stable release | */ - FIRMWARE_VERSION_TYPE_ENUM_END=256, /* | */ -} FIRMWARE_VERSION_TYPE; -#endif - -/** @brief These flags encode the MAV mode. */ -#ifndef HAVE_ENUM_MAV_MODE_FLAG -#define HAVE_ENUM_MAV_MODE_FLAG -typedef enum MAV_MODE_FLAG -{ - MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */ - MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ - MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */ - MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */ - MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */ - MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */ - MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */ - MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state. | */ - MAV_MODE_FLAG_ENUM_END=129, /* | */ -} MAV_MODE_FLAG; -#endif - -/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */ -#ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION -#define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION -typedef enum MAV_MODE_FLAG_DECODE_POSITION -{ - MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */ - MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */ - MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit: 00000100 | */ - MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */ - MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */ - MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */ - MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */ - MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */ - MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */ -} MAV_MODE_FLAG_DECODE_POSITION; -#endif - -/** @brief Override command, pauses current mission execution and moves immediately to a position */ -#ifndef HAVE_ENUM_MAV_GOTO -#define HAVE_ENUM_MAV_GOTO -typedef enum MAV_GOTO -{ - MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */ - MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */ - MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */ - MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */ - MAV_GOTO_ENUM_END=4, /* | */ -} MAV_GOTO; -#endif - -/** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it - simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */ -#ifndef HAVE_ENUM_MAV_MODE -#define HAVE_ENUM_MAV_MODE -typedef enum MAV_MODE -{ - MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */ - MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */ - MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ - MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */ - MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ - MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */ - MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ - MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */ - MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ - MAV_MODE_ENUM_END=221, /* | */ -} MAV_MODE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_STATE -#define HAVE_ENUM_MAV_STATE -typedef enum MAV_STATE -{ - MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */ - MAV_STATE_BOOT=1, /* System is booting up. | */ - MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */ - MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */ - MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */ - MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */ - MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */ - MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */ - MAV_STATE_ENUM_END=8, /* | */ -} MAV_STATE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_COMPONENT -#define HAVE_ENUM_MAV_COMPONENT -typedef enum MAV_COMPONENT -{ - MAV_COMP_ID_ALL=0, /* | */ - MAV_COMP_ID_AUTOPILOT1=1, /* | */ - MAV_COMP_ID_CAMERA=100, /* | */ - MAV_COMP_ID_SERVO1=140, /* | */ - MAV_COMP_ID_SERVO2=141, /* | */ - MAV_COMP_ID_SERVO3=142, /* | */ - MAV_COMP_ID_SERVO4=143, /* | */ - MAV_COMP_ID_SERVO5=144, /* | */ - MAV_COMP_ID_SERVO6=145, /* | */ - MAV_COMP_ID_SERVO7=146, /* | */ - MAV_COMP_ID_SERVO8=147, /* | */ - MAV_COMP_ID_SERVO9=148, /* | */ - MAV_COMP_ID_SERVO10=149, /* | */ - MAV_COMP_ID_SERVO11=150, /* | */ - MAV_COMP_ID_SERVO12=151, /* | */ - MAV_COMP_ID_SERVO13=152, /* | */ - MAV_COMP_ID_SERVO14=153, /* | */ - MAV_COMP_ID_GIMBAL=154, /* | */ - MAV_COMP_ID_LOG=155, /* | */ - MAV_COMP_ID_ADSB=156, /* | */ - MAV_COMP_ID_OSD=157, /* On Screen Display (OSD) devices for video links | */ - MAV_COMP_ID_PERIPHERAL=158, /* Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol | */ - MAV_COMP_ID_QX1_GIMBAL=159, /* | */ - MAV_COMP_ID_MAPPER=180, /* | */ - MAV_COMP_ID_MISSIONPLANNER=190, /* | */ - MAV_COMP_ID_PATHPLANNER=195, /* | */ - MAV_COMP_ID_IMU=200, /* | */ - MAV_COMP_ID_IMU_2=201, /* | */ - MAV_COMP_ID_IMU_3=202, /* | */ - MAV_COMP_ID_GPS=220, /* | */ - MAV_COMP_ID_GPS2=221, /* | */ - MAV_COMP_ID_UDP_BRIDGE=240, /* | */ - MAV_COMP_ID_UART_BRIDGE=241, /* | */ - MAV_COMP_ID_SYSTEM_CONTROL=250, /* | */ - MAV_COMPONENT_ENUM_END=251, /* | */ -} MAV_COMPONENT; -#endif - -/** @brief These encode the sensors whose status is sent as part of the SYS_STATUS message. */ -#ifndef HAVE_ENUM_MAV_SYS_STATUS_SENSOR -#define HAVE_ENUM_MAV_SYS_STATUS_SENSOR -typedef enum MAV_SYS_STATUS_SENSOR -{ - MAV_SYS_STATUS_SENSOR_3D_GYRO=1, /* 0x01 3D gyro | */ - MAV_SYS_STATUS_SENSOR_3D_ACCEL=2, /* 0x02 3D accelerometer | */ - MAV_SYS_STATUS_SENSOR_3D_MAG=4, /* 0x04 3D magnetometer | */ - MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE=8, /* 0x08 absolute pressure | */ - MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE=16, /* 0x10 differential pressure | */ - MAV_SYS_STATUS_SENSOR_GPS=32, /* 0x20 GPS | */ - MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW=64, /* 0x40 optical flow | */ - MAV_SYS_STATUS_SENSOR_VISION_POSITION=128, /* 0x80 computer vision position | */ - MAV_SYS_STATUS_SENSOR_LASER_POSITION=256, /* 0x100 laser based position | */ - MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH=512, /* 0x200 external ground truth (Vicon or Leica) | */ - MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL=1024, /* 0x400 3D angular rate control | */ - MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION=2048, /* 0x800 attitude stabilization | */ - MAV_SYS_STATUS_SENSOR_YAW_POSITION=4096, /* 0x1000 yaw position | */ - MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL=8192, /* 0x2000 z/altitude control | */ - MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL=16384, /* 0x4000 x/y position control | */ - MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS=32768, /* 0x8000 motor outputs / control | */ - MAV_SYS_STATUS_SENSOR_RC_RECEIVER=65536, /* 0x10000 rc receiver | */ - MAV_SYS_STATUS_SENSOR_3D_GYRO2=131072, /* 0x20000 2nd 3D gyro | */ - MAV_SYS_STATUS_SENSOR_3D_ACCEL2=262144, /* 0x40000 2nd 3D accelerometer | */ - MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /* 0x80000 2nd 3D magnetometer | */ - MAV_SYS_STATUS_GEOFENCE=1048576, /* 0x100000 geofence | */ - MAV_SYS_STATUS_AHRS=2097152, /* 0x200000 AHRS subsystem health | */ - MAV_SYS_STATUS_TERRAIN=4194304, /* 0x400000 Terrain subsystem health | */ - MAV_SYS_STATUS_REVERSE_MOTOR=8388608, /* 0x800000 Motors are reversed | */ - MAV_SYS_STATUS_LOGGING=16777216, /* 0x1000000 Logging | */ - MAV_SYS_STATUS_SENSOR_BATTERY=33554432, /* 0x2000000 Battery | */ - MAV_SYS_STATUS_SENSOR_ENUM_END=33554433, /* | */ -} MAV_SYS_STATUS_SENSOR; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_FRAME -#define HAVE_ENUM_MAV_FRAME -typedef enum MAV_FRAME -{ - MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */ - MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */ - MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */ - MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */ - MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */ - MAV_FRAME_GLOBAL_INT=5, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) | */ - MAV_FRAME_GLOBAL_RELATIVE_ALT_INT=6, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. | */ - MAV_FRAME_LOCAL_OFFSET_NED=7, /* Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. | */ - MAV_FRAME_BODY_NED=8, /* Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. | */ - MAV_FRAME_BODY_OFFSET_NED=9, /* Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. | */ - MAV_FRAME_GLOBAL_TERRAIN_ALT=10, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ - MAV_FRAME_GLOBAL_TERRAIN_ALT_INT=11, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ - MAV_FRAME_ENUM_END=12, /* | */ -} MAV_FRAME; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE -#define HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE -typedef enum MAVLINK_DATA_STREAM_TYPE -{ - MAVLINK_DATA_STREAM_IMG_JPEG=1, /* | */ - MAVLINK_DATA_STREAM_IMG_BMP=2, /* | */ - MAVLINK_DATA_STREAM_IMG_RAW8U=3, /* | */ - MAVLINK_DATA_STREAM_IMG_RAW32U=4, /* | */ - MAVLINK_DATA_STREAM_IMG_PGM=5, /* | */ - MAVLINK_DATA_STREAM_IMG_PNG=6, /* | */ - MAVLINK_DATA_STREAM_TYPE_ENUM_END=7, /* | */ -} MAVLINK_DATA_STREAM_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_FENCE_ACTION -#define HAVE_ENUM_FENCE_ACTION -typedef enum FENCE_ACTION -{ - FENCE_ACTION_NONE=0, /* Disable fenced mode | */ - FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */ - FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */ - FENCE_ACTION_GUIDED_THR_PASS=3, /* Switched to guided mode to return point (fence point 0) with manual throttle control | */ - FENCE_ACTION_RTL=4, /* Switch to RTL (return to launch) mode and head for the return point. | */ - FENCE_ACTION_ENUM_END=5, /* | */ -} FENCE_ACTION; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_FENCE_BREACH -#define HAVE_ENUM_FENCE_BREACH -typedef enum FENCE_BREACH -{ - FENCE_BREACH_NONE=0, /* No last fence breach | */ - FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */ - FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */ - FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */ - FENCE_BREACH_ENUM_END=4, /* | */ -} FENCE_BREACH; -#endif - -/** @brief Enumeration of possible mount operation modes */ -#ifndef HAVE_ENUM_MAV_MOUNT_MODE -#define HAVE_ENUM_MAV_MOUNT_MODE -typedef enum MAV_MOUNT_MODE -{ - MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */ - MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */ - MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */ - MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */ - MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */ - MAV_MOUNT_MODE_ENUM_END=5, /* | */ -} MAV_MOUNT_MODE; -#endif - -/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ -#ifndef HAVE_ENUM_MAV_CMD -#define HAVE_ENUM_MAV_CMD -typedef enum MAV_CMD -{ - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing). NaN for unchanged.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Abort Alt| Empty| Empty| Desired yaw angle. NaN for unchanged.| 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. NaN for unchanged.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate [ms^-1]| Desired yaw angle [rad]| Y-axis position [m]| X-axis position [m]| Z-axis / ground level position [m]| */ - MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]| Empty| Takeoff ascend rate [ms^-1]| Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position [m]| X-axis position [m]| Z-axis position [m]| */ - MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. | Empty| Empty| Empty| Empty| Empty| Desired altitude in meters| */ - MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Heading Required (0 = False)| Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_FOLLOW=32, /* Being following a target |System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode| RESERVED| RESERVED| altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home| altitude| RESERVED| TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout| */ - MAV_CMD_DO_FOLLOW_REPOSITION=33, /* Reposition the MAV after a follow target command has been sent |Camera q1 (where 0 is on the ray from the camera to the tracking device)| Camera q2| Camera q3| Camera q4| altitude offset from target (m)| X offset from target (m)| Y offset from target (m)| */ - MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_VTOL_TAKEOFF=84, /* Takeoff from ground using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees. NaN for unchanged.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees. NaN for unchanged.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty| */ - MAV_CMD_NAV_PAYLOAD_PLACE=94, /* Descend and place payload. Vehicle descends until it detects a hanging payload has reached the ground, the gripper is opened to release the payload |Maximum distance to descend (meters)| Empty| Empty| Empty| Latitude (deg * 1E7)| Longitude (deg * 1E7)| Altitude (meters)| */ - 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| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| absolute or relative [0,1]| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_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_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_ALTITUDE=186, /* Change altitude set point. |Altitude in meters| Mav frame of new altitude (see MAV_FRAME)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */ - MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPOSITION=192, /* Reposition the vehicle to a specific WGS84 global position. |Ground speed, less than 0 (-1) for default| Bitmask of option flags, see the MAV_DO_REPOSITION_FLAGS enum.| Reserved| Yaw heading, NaN for unchanged. For planes indicates loiter direction (0: clockwise, 1: counter clockwise)| Latitude (deg * 1E7)| Longitude (deg * 1E7)| Altitude (meters)| */ - MAV_CMD_DO_PAUSE_CONTINUE=193, /* If in a GPS controlled position mode, hold the current position or continue. |0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_DO_SET_REVERSE=194, /* Set moving direction to forward or reverse. |Direction (0=Forward, 1=Reverse)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ - MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Test shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count.| */ - MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch (WIP: DEPRECATED: or lat in degrees) depending on mount mode.| roll (WIP: DEPRECATED: or lon in degrees) depending on mount mode.| yaw (WIP: DEPRECATED: or alt in meters) depending on mount mode.| WIP: alt in meters depending on mount mode.| WIP: latitude in degrees * 1E7, set if appropriate mount mode.| WIP: longitude in degrees * 1E7, set if appropriate mount mode.| MAV_MOUNT_MODE enum value| */ - MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set camera trigger distance for this flight. The camera is trigerred each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera. |Camera trigger distance (meters). -1 or 0 to ignore| Camera shutter integration time (milliseconds). -1 or 0 to ignore| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable, 2=disable_floor_only)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOTOR_TEST=209, /* Mission command to perform motor test |motor sequence number (a number from 1 to max number of motors on the vehicle)| throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)| throttle| timeout (in seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_SET_YAW_SPEED=213, /* Sets a desired vehicle turn angle and speed change |yaw angle to adjust steering by in centidegress| speed - normalized to 0 .. 1| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL=214, /* Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera. |Camera trigger cycle time (milliseconds). -1 or 0 to ignore.| Camera shutter integration time (milliseconds). Should be less than trigger cycle time. -1 or 0 to ignore.| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */ - MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */ - MAV_CMD_DO_ENGINE_CONTROL=223, /* Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines |0: Stop engine, 1:Start Engine| 0: Warm start, 1:Cold start. Controls use of choke where applicable| Height delay (meters). This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay.| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero. |1: gyro calibration, 3: gyro temperature calibration| 1: magnetometer calibration| 1: ground pressure calibration| 1: radio RC calibration, 2: RC trim calibration| 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration| 1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration| 1: ESC calibration, 3: barometer temperature calibration| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. |1: Trigger actuator ID assignment and direction mapping.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.| WIP: 0: Do nothing for camera, 1: Reboot onboard camera, 2: Shutdown onboard camera, 3: Reboot onboard camera and keep it in the bootloader until upgraded| WIP: 0: Do nothing for mount (e.g. gimbal), 1: Reboot mount, 2: Shutdown mount, 3: Reboot mount and keep it in the bootloader until upgraded| Reserved, send 0| Reserved, send 0| WIP: ID (e.g. camera ID -1 for all IDs)| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ - MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID| */ - MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.| */ - MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */ - MAV_CMD_REQUEST_CAMERA_INFORMATION=521, /* WIP: Request camera information (CAMERA_INFORMATION) |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| 0: No action 1: Request camera capabilities| Reserved (all remaining params)| */ - MAV_CMD_REQUEST_CAMERA_SETTINGS=522, /* WIP: Request camera settings (CAMERA_SETTINGS) |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| 0: No Action 1: Request camera settings| Reserved (all remaining params)| */ - MAV_CMD_SET_CAMERA_SETTINGS_1=523, /* WIP: Set the camera settings part 1 (CAMERA_SETTINGS). Use NAN for values you don't want to change. |Camera ID (1 for first, 2 for second, etc.)| Aperture (1/value)| Shutter speed in seconds| ISO sensitivity| AE mode (Auto Exposure) (0: full auto 1: full manual 2: aperture priority 3: shutter priority)| EV value (when in auto exposure)| White balance (color temperature in K) (0: Auto WB)| */ - MAV_CMD_SET_CAMERA_SETTINGS_2=524, /* WIP: Set the camera settings part 2 (CAMERA_SETTINGS). Use NAN for values you don't want to change. |Camera ID (1 for first, 2 for second, etc.)| Camera mode (0: photo, 1: video)| Audio recording enabled (0: off 1: on)| Reserved for metering mode ID (Average, Center, Spot, etc.)| Reserved for image format ID (Jpeg/Raw/Jpeg+Raw)| Reserved for image quality ID (Compression)| Reserved for color mode ID (Neutral, Vivid, etc.)| */ - MAV_CMD_REQUEST_STORAGE_INFORMATION=525, /* WIP: Request storage information (STORAGE_INFORMATION) |Storage ID (0 for all, 1 for first, 2 for second, etc.)| 0: No Action 1: Request storage information| Reserved (all remaining params)| */ - MAV_CMD_STORAGE_FORMAT=526, /* WIP: Format a storage medium |Storage ID (1 for first, 2 for second, etc.)| 0: No action 1: Format storage| Reserved (all remaining params)| */ - MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS=527, /* WIP: Request camera capture status (CAMERA_CAPTURE_STATUS) |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| 0: No Action 1: Request camera capture status| Reserved (all remaining params)| */ - MAV_CMD_REQUEST_FLIGHT_INFORMATION=528, /* WIP: Request flight information (FLIGHT_INFORMATION) |1: Request flight information| Reserved (all remaining params)| */ - MAV_CMD_RESET_CAMERA_SETTINGS=529, /* WIP: Reset all camera settings to Factory Default (CAMERA_SETTINGS) |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| 0: No Action 1: Reset all settings| Reserved (all remaining params)| */ - MAV_CMD_IMAGE_START_CAPTURE=2000, /* WIP: Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| Duration between two consecutive pictures (in seconds)| Number of images to capture total - 0 for unlimited capture| Resolution horizontal in pixels (set to -1 for highest resolution possible)| Resolution vertical in pixels (set to -1 for highest resolution possible)| */ - MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* WIP: Stop image capture sequence |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| Reserved| */ - MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE=2002, /* WIP: Re-request a CAMERA_IMAGE_CAPTURE packet |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| Sequence number for missing CAMERA_IMAGE_CAPTURE packet| Reserved (all remaining params)| */ - MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start), -1 to ignore| 1 to reset the trigger sequence, -1 or 0 to ignore| 1 to pause triggering, but without switching the camera off or retracting it. -1 to ignore| */ - MAV_CMD_VIDEO_START_CAPTURE=2500, /* WIP: Starts video capture (recording) |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| Frames per second, set to -1 for highest framerate possible.| Resolution horizontal in pixels (set to -1 for highest resolution possible)| Resolution vertical in pixels (set to -1 for highest resolution possible)| Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise time in Hz)| */ - MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* WIP: Stop the current video capture (recording) |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| Reserved| */ - MAV_CMD_VIDEO_START_STREAMING=2502, /* WIP: Start video streaming |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| Reserved| */ - MAV_CMD_VIDEO_STOP_STREAMING=2503, /* WIP: Stop the current video streaming |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| Reserved| */ - MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION=2504, /* WIP: Request video stream information (VIDEO_STREAM_INFORMATION) |Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)| 0: No Action 1: Request video stream information| Reserved (all remaining params)| */ - MAV_CMD_LOGGING_START=2510, /* Request to start streaming logging data over MAVLink (see also LOGGING_DATA message) |Format: 0: ULog| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */ - MAV_CMD_LOGGING_STOP=2511, /* Request to stop streaming log data over MAVLink |Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */ - MAV_CMD_AIRFRAME_CONFIGURATION=2520, /* |Landing gear ID (default: 0, -1 for all)| Landing gear position (Down: 0, Up: 1, NAN for no change)| Reserved, set to NAN| Reserved, set to NAN| Reserved, set to NAN| Reserved, set to NAN| Reserved, set to NAN| */ - MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */ - MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| */ - MAV_CMD_SET_GUIDED_SUBMODE_STANDARD=4000, /* This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocites along all three axes. - | */ - MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE=4001, /* This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position. - |Radius of desired circle in CIRCLE_MODE| User defined| User defined| User defined| Unscaled target latitude of center of circle in CIRCLE_MODE| Unscaled target longitude of center of circle in CIRCLE_MODE| */ - MAV_CMD_NAV_FENCE_RETURN_POINT=5000, /* Fence return point. There can only be one fence return point. - |Reserved| Reserved| Reserved| Reserved| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION=5001, /* Fence vertex for an inclusion polygon. The vehicle must stay within this area. Minimum of 3 vertices required. - |Polygon vertex count| Reserved| Reserved| Reserved| Latitude| Longitude| Reserved| */ - MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION=5002, /* Fence vertex for an exclusion polygon. The vehicle must stay outside this area. Minimum of 3 vertices required. - |Polygon vertex count| Reserved| Reserved| Reserved| Latitude| Longitude| Reserved| */ - MAV_CMD_NAV_RALLY_POINT=5100, /* Rally point. You can have multiple rally points defined. - |Reserved| Reserved| Reserved| Reserved| Latitude| Longitude| Altitude| */ - MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */ - MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_WAYPOINT_USER_1=31000, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_WAYPOINT_USER_2=31001, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_WAYPOINT_USER_3=31002, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_WAYPOINT_USER_4=31003, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_WAYPOINT_USER_5=31004, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_SPATIAL_USER_1=31005, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_SPATIAL_USER_2=31006, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_SPATIAL_USER_3=31007, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_SPATIAL_USER_4=31008, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_SPATIAL_USER_5=31009, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ - MAV_CMD_USER_1=31010, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ - MAV_CMD_USER_2=31011, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ - MAV_CMD_USER_3=31012, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ - MAV_CMD_USER_4=31013, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ - MAV_CMD_USER_5=31014, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ - MAV_CMD_ENUM_END=31015, /* | */ -} MAV_CMD; -#endif - -/** @brief THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a - recommendation to the autopilot software. Individual autopilots may or may not obey - the recommended messages. */ -#ifndef HAVE_ENUM_MAV_DATA_STREAM -#define HAVE_ENUM_MAV_DATA_STREAM -typedef enum MAV_DATA_STREAM -{ - MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ - MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ - MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ - MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ - MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ - MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */ - MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_ENUM_END=13, /* | */ -} MAV_DATA_STREAM; -#endif - -/** @brief The ROI (region of interest) for the vehicle. This can be - be used by the vehicle for camera/vehicle attitude alignment (see - MAV_CMD_NAV_ROI). */ -#ifndef HAVE_ENUM_MAV_ROI -#define HAVE_ENUM_MAV_ROI -typedef enum MAV_ROI -{ - MAV_ROI_NONE=0, /* No region of interest. | */ - MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */ - MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */ - MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ - MAV_ROI_TARGET=4, /* Point toward of given id. | */ - MAV_ROI_ENUM_END=5, /* | */ -} MAV_ROI; -#endif - -/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */ -#ifndef HAVE_ENUM_MAV_CMD_ACK -#define HAVE_ENUM_MAV_CMD_ACK -typedef enum MAV_CMD_ACK -{ - MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */ - MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ - MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */ - MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */ - MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */ - MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */ - MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */ - MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */ - MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */ - MAV_CMD_ACK_ENUM_END=10, /* | */ -} MAV_CMD_ACK; -#endif - -/** @brief Specifies the datatype of a MAVLink parameter. */ -#ifndef HAVE_ENUM_MAV_PARAM_TYPE -#define HAVE_ENUM_MAV_PARAM_TYPE -typedef enum MAV_PARAM_TYPE -{ - MAV_PARAM_TYPE_UINT8=1, /* 8-bit unsigned integer | */ - MAV_PARAM_TYPE_INT8=2, /* 8-bit signed integer | */ - MAV_PARAM_TYPE_UINT16=3, /* 16-bit unsigned integer | */ - MAV_PARAM_TYPE_INT16=4, /* 16-bit signed integer | */ - MAV_PARAM_TYPE_UINT32=5, /* 32-bit unsigned integer | */ - MAV_PARAM_TYPE_INT32=6, /* 32-bit signed integer | */ - MAV_PARAM_TYPE_UINT64=7, /* 64-bit unsigned integer | */ - MAV_PARAM_TYPE_INT64=8, /* 64-bit signed integer | */ - MAV_PARAM_TYPE_REAL32=9, /* 32-bit floating-point | */ - MAV_PARAM_TYPE_REAL64=10, /* 64-bit floating-point | */ - MAV_PARAM_TYPE_ENUM_END=11, /* | */ -} MAV_PARAM_TYPE; -#endif - -/** @brief result from a mavlink command */ -#ifndef HAVE_ENUM_MAV_RESULT -#define HAVE_ENUM_MAV_RESULT -typedef enum MAV_RESULT -{ - MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ - MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ - MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */ - MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ - MAV_RESULT_FAILED=4, /* Command executed, but failed | */ - MAV_RESULT_IN_PROGRESS=5, /* WIP: Command being executed | */ - MAV_RESULT_ENUM_END=6, /* | */ -} MAV_RESULT; -#endif - -/** @brief result in a mavlink mission ack */ -#ifndef HAVE_ENUM_MAV_MISSION_RESULT -#define HAVE_ENUM_MAV_MISSION_RESULT -typedef enum MAV_MISSION_RESULT -{ - MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ - MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ - MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */ - MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */ - MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */ - MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */ - MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */ - MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */ - MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */ - MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */ - MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */ - MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */ - MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */ - MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ - MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ - MAV_MISSION_RESULT_ENUM_END=15, /* | */ -} MAV_MISSION_RESULT; -#endif - -/** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ -#ifndef HAVE_ENUM_MAV_SEVERITY -#define HAVE_ENUM_MAV_SEVERITY -typedef enum MAV_SEVERITY -{ - MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */ - MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ - MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */ - MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */ - MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */ - MAV_SEVERITY_NOTICE=5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */ - MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ - MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ - MAV_SEVERITY_ENUM_END=8, /* | */ -} MAV_SEVERITY; -#endif - -/** @brief Power supply status flags (bitmask) */ -#ifndef HAVE_ENUM_MAV_POWER_STATUS -#define HAVE_ENUM_MAV_POWER_STATUS -typedef enum MAV_POWER_STATUS -{ - MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */ - MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */ - MAV_POWER_STATUS_USB_CONNECTED=4, /* USB power is connected | */ - MAV_POWER_STATUS_PERIPH_OVERCURRENT=8, /* peripheral supply is in over-current state | */ - MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */ - MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */ - MAV_POWER_STATUS_ENUM_END=33, /* | */ -} MAV_POWER_STATUS; -#endif - -/** @brief SERIAL_CONTROL device types */ -#ifndef HAVE_ENUM_SERIAL_CONTROL_DEV -#define HAVE_ENUM_SERIAL_CONTROL_DEV -typedef enum SERIAL_CONTROL_DEV -{ - SERIAL_CONTROL_DEV_TELEM1=0, /* First telemetry port | */ - SERIAL_CONTROL_DEV_TELEM2=1, /* Second telemetry port | */ - SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */ - SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */ - SERIAL_CONTROL_DEV_SHELL=10, /* system shell | */ - SERIAL_CONTROL_DEV_ENUM_END=11, /* | */ -} SERIAL_CONTROL_DEV; -#endif - -/** @brief SERIAL_CONTROL flags (bitmask) */ -#ifndef HAVE_ENUM_SERIAL_CONTROL_FLAG -#define HAVE_ENUM_SERIAL_CONTROL_FLAG -typedef enum SERIAL_CONTROL_FLAG -{ - SERIAL_CONTROL_FLAG_REPLY=1, /* Set if this is a reply | */ - SERIAL_CONTROL_FLAG_RESPOND=2, /* Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | */ - SERIAL_CONTROL_FLAG_EXCLUSIVE=4, /* Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set | */ - SERIAL_CONTROL_FLAG_BLOCKING=8, /* Block on writes to the serial port | */ - SERIAL_CONTROL_FLAG_MULTI=16, /* Send multiple replies until port is drained | */ - SERIAL_CONTROL_FLAG_ENUM_END=17, /* | */ -} SERIAL_CONTROL_FLAG; -#endif - -/** @brief Enumeration of distance sensor types */ -#ifndef HAVE_ENUM_MAV_DISTANCE_SENSOR -#define HAVE_ENUM_MAV_DISTANCE_SENSOR -typedef enum MAV_DISTANCE_SENSOR -{ - MAV_DISTANCE_SENSOR_LASER=0, /* Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units | */ - MAV_DISTANCE_SENSOR_ULTRASOUND=1, /* Ultrasound rangefinder, e.g. MaxBotix units | */ - MAV_DISTANCE_SENSOR_INFRARED=2, /* Infrared rangefinder, e.g. Sharp units | */ - MAV_DISTANCE_SENSOR_ENUM_END=3, /* | */ -} MAV_DISTANCE_SENSOR; -#endif - -/** @brief Enumeration of sensor orientation, according to its rotations */ -#ifndef HAVE_ENUM_MAV_SENSOR_ORIENTATION -#define HAVE_ENUM_MAV_SENSOR_ORIENTATION -typedef enum MAV_SENSOR_ORIENTATION -{ - MAV_SENSOR_ROTATION_NONE=0, /* Roll: 0, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_YAW_45=1, /* Roll: 0, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_YAW_90=2, /* Roll: 0, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_YAW_135=3, /* Roll: 0, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_YAW_180=4, /* Roll: 0, Pitch: 0, Yaw: 180 | */ - MAV_SENSOR_ROTATION_YAW_225=5, /* Roll: 0, Pitch: 0, Yaw: 225 | */ - MAV_SENSOR_ROTATION_YAW_270=6, /* Roll: 0, Pitch: 0, Yaw: 270 | */ - MAV_SENSOR_ROTATION_YAW_315=7, /* Roll: 0, Pitch: 0, Yaw: 315 | */ - MAV_SENSOR_ROTATION_ROLL_180=8, /* Roll: 180, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_45=9, /* Roll: 180, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_90=10, /* Roll: 180, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_135=11, /* Roll: 180, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_PITCH_180=12, /* Roll: 0, Pitch: 180, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_225=13, /* Roll: 180, Pitch: 0, Yaw: 225 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_270=14, /* Roll: 180, Pitch: 0, Yaw: 270 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_315=15, /* Roll: 180, Pitch: 0, Yaw: 315 | */ - MAV_SENSOR_ROTATION_ROLL_90=16, /* Roll: 90, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_45=17, /* Roll: 90, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_90=18, /* Roll: 90, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_135=19, /* Roll: 90, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_ROLL_270=20, /* Roll: 270, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_YAW_45=21, /* Roll: 270, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_ROLL_270_YAW_90=22, /* Roll: 270, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_270_YAW_135=23, /* Roll: 270, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_PITCH_90=24, /* Roll: 0, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_PITCH_270=25, /* Roll: 0, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_PITCH_180_YAW_90=26, /* Roll: 0, Pitch: 180, Yaw: 90 | */ - MAV_SENSOR_ROTATION_PITCH_180_YAW_270=27, /* Roll: 0, Pitch: 180, Yaw: 270 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_90=28, /* Roll: 90, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_PITCH_90=29, /* Roll: 180, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_PITCH_90=30, /* Roll: 270, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_180=31, /* Roll: 90, Pitch: 180, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_PITCH_180=32, /* Roll: 270, Pitch: 180, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_270=33, /* Roll: 90, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_PITCH_270=34, /* Roll: 180, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_PITCH_270=35, /* Roll: 270, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90=36, /* Roll: 90, Pitch: 180, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_270=37, /* Roll: 90, Pitch: 0, Yaw: 270 | */ - MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315=38, /* Roll: 315, Pitch: 315, Yaw: 315 | */ - MAV_SENSOR_ORIENTATION_ENUM_END=39, /* | */ -} MAV_SENSOR_ORIENTATION; -#endif - -/** @brief Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. */ -#ifndef HAVE_ENUM_MAV_PROTOCOL_CAPABILITY -#define HAVE_ENUM_MAV_PROTOCOL_CAPABILITY -typedef enum MAV_PROTOCOL_CAPABILITY -{ - MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT=1, /* Autopilot supports MISSION float message type. | */ - MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT=2, /* Autopilot supports the new param float message type. | */ - MAV_PROTOCOL_CAPABILITY_MISSION_INT=4, /* Autopilot supports MISSION_INT scaled integer message type. | */ - MAV_PROTOCOL_CAPABILITY_COMMAND_INT=8, /* Autopilot supports COMMAND_INT scaled integer message type. | */ - MAV_PROTOCOL_CAPABILITY_PARAM_UNION=16, /* Autopilot supports the new param union message type. | */ - MAV_PROTOCOL_CAPABILITY_FTP=32, /* Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. | */ - MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET=64, /* Autopilot supports commanding attitude offboard. | */ - MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED=128, /* Autopilot supports commanding position and velocity targets in local NED frame. | */ - MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT=256, /* Autopilot supports commanding position and velocity targets in global scaled integers. | */ - MAV_PROTOCOL_CAPABILITY_TERRAIN=512, /* Autopilot supports terrain protocol / data handling. | */ - MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET=1024, /* Autopilot supports direct actuator control. | */ - MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION=2048, /* Autopilot supports the flight termination command. | */ - MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION=4096, /* Autopilot supports onboard compass calibration. | */ - MAV_PROTOCOL_CAPABILITY_MAVLINK2=8192, /* Autopilot supports mavlink version 2. | */ - MAV_PROTOCOL_CAPABILITY_MISSION_FENCE=16384, /* Autopilot supports mission fence protocol. | */ - MAV_PROTOCOL_CAPABILITY_MISSION_RALLY=32768, /* Autopilot supports mission rally point protocol. | */ - MAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION=65536, /* Autopilot supports the flight information protocol. | */ - MAV_PROTOCOL_CAPABILITY_ENUM_END=65537, /* | */ -} MAV_PROTOCOL_CAPABILITY; -#endif - -/** @brief Type of mission items being requested/sent in mission protocol. */ -#ifndef HAVE_ENUM_MAV_MISSION_TYPE -#define HAVE_ENUM_MAV_MISSION_TYPE -typedef enum MAV_MISSION_TYPE -{ - MAV_MISSION_TYPE_MISSION=0, /* Items are mission commands for main mission. | */ - MAV_MISSION_TYPE_FENCE=1, /* Specifies GeoFence area(s). Items are MAV_CMD_FENCE_ GeoFence items. | */ - MAV_MISSION_TYPE_RALLY=2, /* Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_RALLY_POINT rally point items. | */ - MAV_MISSION_TYPE_ALL=255, /* Only used in MISSION_CLEAR_ALL to clear all mission types. | */ - MAV_MISSION_TYPE_ENUM_END=256, /* | */ -} MAV_MISSION_TYPE; -#endif - -/** @brief Enumeration of estimator types */ -#ifndef HAVE_ENUM_MAV_ESTIMATOR_TYPE -#define HAVE_ENUM_MAV_ESTIMATOR_TYPE -typedef enum MAV_ESTIMATOR_TYPE -{ - MAV_ESTIMATOR_TYPE_NAIVE=1, /* This is a naive estimator without any real covariance feedback. | */ - MAV_ESTIMATOR_TYPE_VISION=2, /* Computer vision based estimate. Might be up to scale. | */ - MAV_ESTIMATOR_TYPE_VIO=3, /* Visual-inertial estimate. | */ - MAV_ESTIMATOR_TYPE_GPS=4, /* Plain GPS estimate. | */ - MAV_ESTIMATOR_TYPE_GPS_INS=5, /* Estimator integrating GPS and inertial sensing. | */ - MAV_ESTIMATOR_TYPE_ENUM_END=6, /* | */ -} MAV_ESTIMATOR_TYPE; -#endif - -/** @brief Enumeration of battery types */ -#ifndef HAVE_ENUM_MAV_BATTERY_TYPE -#define HAVE_ENUM_MAV_BATTERY_TYPE -typedef enum MAV_BATTERY_TYPE -{ - MAV_BATTERY_TYPE_UNKNOWN=0, /* Not specified. | */ - MAV_BATTERY_TYPE_LIPO=1, /* Lithium polymer battery | */ - MAV_BATTERY_TYPE_LIFE=2, /* Lithium-iron-phosphate battery | */ - MAV_BATTERY_TYPE_LION=3, /* Lithium-ION battery | */ - MAV_BATTERY_TYPE_NIMH=4, /* Nickel metal hydride battery | */ - MAV_BATTERY_TYPE_ENUM_END=5, /* | */ -} MAV_BATTERY_TYPE; -#endif - -/** @brief Enumeration of battery functions */ -#ifndef HAVE_ENUM_MAV_BATTERY_FUNCTION -#define HAVE_ENUM_MAV_BATTERY_FUNCTION -typedef enum MAV_BATTERY_FUNCTION -{ - MAV_BATTERY_FUNCTION_UNKNOWN=0, /* Battery function is unknown | */ - MAV_BATTERY_FUNCTION_ALL=1, /* Battery supports all flight systems | */ - MAV_BATTERY_FUNCTION_PROPULSION=2, /* Battery for the propulsion system | */ - MAV_BATTERY_FUNCTION_AVIONICS=3, /* Avionics battery | */ - MAV_BATTERY_TYPE_PAYLOAD=4, /* Payload battery | */ - MAV_BATTERY_FUNCTION_ENUM_END=5, /* | */ -} MAV_BATTERY_FUNCTION; -#endif - -/** @brief Enumeration of VTOL states */ -#ifndef HAVE_ENUM_MAV_VTOL_STATE -#define HAVE_ENUM_MAV_VTOL_STATE -typedef enum MAV_VTOL_STATE -{ - MAV_VTOL_STATE_UNDEFINED=0, /* MAV is not configured as VTOL | */ - MAV_VTOL_STATE_TRANSITION_TO_FW=1, /* VTOL is in transition from multicopter to fixed-wing | */ - MAV_VTOL_STATE_TRANSITION_TO_MC=2, /* VTOL is in transition from fixed-wing to multicopter | */ - MAV_VTOL_STATE_MC=3, /* VTOL is in multicopter state | */ - MAV_VTOL_STATE_FW=4, /* VTOL is in fixed-wing state | */ - MAV_VTOL_STATE_ENUM_END=5, /* | */ -} MAV_VTOL_STATE; -#endif - -/** @brief Enumeration of landed detector states */ -#ifndef HAVE_ENUM_MAV_LANDED_STATE -#define HAVE_ENUM_MAV_LANDED_STATE -typedef enum MAV_LANDED_STATE -{ - MAV_LANDED_STATE_UNDEFINED=0, /* MAV landed state is unknown | */ - MAV_LANDED_STATE_ON_GROUND=1, /* MAV is landed (on ground) | */ - MAV_LANDED_STATE_IN_AIR=2, /* MAV is in air | */ - MAV_LANDED_STATE_TAKEOFF=3, /* MAV currently taking off | */ - MAV_LANDED_STATE_LANDING=4, /* MAV currently landing | */ - MAV_LANDED_STATE_ENUM_END=5, /* | */ -} MAV_LANDED_STATE; -#endif - -/** @brief Enumeration of the ADSB altimeter types */ -#ifndef HAVE_ENUM_ADSB_ALTITUDE_TYPE -#define HAVE_ENUM_ADSB_ALTITUDE_TYPE -typedef enum ADSB_ALTITUDE_TYPE -{ - ADSB_ALTITUDE_TYPE_PRESSURE_QNH=0, /* Altitude reported from a Baro source using QNH reference | */ - ADSB_ALTITUDE_TYPE_GEOMETRIC=1, /* Altitude reported from a GNSS source | */ - ADSB_ALTITUDE_TYPE_ENUM_END=2, /* | */ -} ADSB_ALTITUDE_TYPE; -#endif - -/** @brief ADSB classification for the type of vehicle emitting the transponder signal */ -#ifndef HAVE_ENUM_ADSB_EMITTER_TYPE -#define HAVE_ENUM_ADSB_EMITTER_TYPE -typedef enum ADSB_EMITTER_TYPE -{ - ADSB_EMITTER_TYPE_NO_INFO=0, /* | */ - ADSB_EMITTER_TYPE_LIGHT=1, /* | */ - ADSB_EMITTER_TYPE_SMALL=2, /* | */ - ADSB_EMITTER_TYPE_LARGE=3, /* | */ - ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE=4, /* | */ - ADSB_EMITTER_TYPE_HEAVY=5, /* | */ - ADSB_EMITTER_TYPE_HIGHLY_MANUV=6, /* | */ - ADSB_EMITTER_TYPE_ROTOCRAFT=7, /* | */ - ADSB_EMITTER_TYPE_UNASSIGNED=8, /* | */ - ADSB_EMITTER_TYPE_GLIDER=9, /* | */ - ADSB_EMITTER_TYPE_LIGHTER_AIR=10, /* | */ - ADSB_EMITTER_TYPE_PARACHUTE=11, /* | */ - ADSB_EMITTER_TYPE_ULTRA_LIGHT=12, /* | */ - ADSB_EMITTER_TYPE_UNASSIGNED2=13, /* | */ - ADSB_EMITTER_TYPE_UAV=14, /* | */ - ADSB_EMITTER_TYPE_SPACE=15, /* | */ - ADSB_EMITTER_TYPE_UNASSGINED3=16, /* | */ - ADSB_EMITTER_TYPE_EMERGENCY_SURFACE=17, /* | */ - ADSB_EMITTER_TYPE_SERVICE_SURFACE=18, /* | */ - ADSB_EMITTER_TYPE_POINT_OBSTACLE=19, /* | */ - ADSB_EMITTER_TYPE_ENUM_END=20, /* | */ -} ADSB_EMITTER_TYPE; -#endif - -/** @brief These flags indicate status such as data validity of each data source. Set = data valid */ -#ifndef HAVE_ENUM_ADSB_FLAGS -#define HAVE_ENUM_ADSB_FLAGS -typedef enum ADSB_FLAGS -{ - ADSB_FLAGS_VALID_COORDS=1, /* | */ - ADSB_FLAGS_VALID_ALTITUDE=2, /* | */ - ADSB_FLAGS_VALID_HEADING=4, /* | */ - ADSB_FLAGS_VALID_VELOCITY=8, /* | */ - ADSB_FLAGS_VALID_CALLSIGN=16, /* | */ - ADSB_FLAGS_VALID_SQUAWK=32, /* | */ - ADSB_FLAGS_SIMULATED=64, /* | */ - ADSB_FLAGS_ENUM_END=65, /* | */ -} ADSB_FLAGS; -#endif - -/** @brief Bitmask of options for the MAV_CMD_DO_REPOSITION */ -#ifndef HAVE_ENUM_MAV_DO_REPOSITION_FLAGS -#define HAVE_ENUM_MAV_DO_REPOSITION_FLAGS -typedef enum MAV_DO_REPOSITION_FLAGS -{ - MAV_DO_REPOSITION_FLAGS_CHANGE_MODE=1, /* The aircraft should immediately transition into guided. This should not be set for follow me applications | */ - MAV_DO_REPOSITION_FLAGS_ENUM_END=2, /* | */ -} MAV_DO_REPOSITION_FLAGS; -#endif - -/** @brief Flags in EKF_STATUS message */ -#ifndef HAVE_ENUM_ESTIMATOR_STATUS_FLAGS -#define HAVE_ENUM_ESTIMATOR_STATUS_FLAGS -typedef enum ESTIMATOR_STATUS_FLAGS -{ - ESTIMATOR_ATTITUDE=1, /* True if the attitude estimate is good | */ - ESTIMATOR_VELOCITY_HORIZ=2, /* True if the horizontal velocity estimate is good | */ - ESTIMATOR_VELOCITY_VERT=4, /* True if the vertical velocity estimate is good | */ - ESTIMATOR_POS_HORIZ_REL=8, /* True if the horizontal position (relative) estimate is good | */ - ESTIMATOR_POS_HORIZ_ABS=16, /* True if the horizontal position (absolute) estimate is good | */ - ESTIMATOR_POS_VERT_ABS=32, /* True if the vertical position (absolute) estimate is good | */ - ESTIMATOR_POS_VERT_AGL=64, /* True if the vertical position (above ground) estimate is good | */ - ESTIMATOR_CONST_POS_MODE=128, /* True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) | */ - ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */ - ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */ - ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */ - ESTIMATOR_STATUS_FLAGS_ENUM_END=1025, /* | */ -} ESTIMATOR_STATUS_FLAGS; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE -#define HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE -typedef enum MOTOR_TEST_THROTTLE_TYPE -{ - MOTOR_TEST_THROTTLE_PERCENT=0, /* throttle as a percentage from 0 ~ 100 | */ - MOTOR_TEST_THROTTLE_PWM=1, /* throttle as an absolute PWM value (normally in range of 1000~2000) | */ - MOTOR_TEST_THROTTLE_PILOT=2, /* throttle pass-through from pilot's transmitter | */ - MOTOR_TEST_THROTTLE_TYPE_ENUM_END=3, /* | */ -} MOTOR_TEST_THROTTLE_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_GPS_INPUT_IGNORE_FLAGS -#define HAVE_ENUM_GPS_INPUT_IGNORE_FLAGS -typedef enum GPS_INPUT_IGNORE_FLAGS -{ - GPS_INPUT_IGNORE_FLAG_ALT=1, /* ignore altitude field | */ - GPS_INPUT_IGNORE_FLAG_HDOP=2, /* ignore hdop field | */ - GPS_INPUT_IGNORE_FLAG_VDOP=4, /* ignore vdop field | */ - GPS_INPUT_IGNORE_FLAG_VEL_HORIZ=8, /* ignore horizontal velocity field (vn and ve) | */ - GPS_INPUT_IGNORE_FLAG_VEL_VERT=16, /* ignore vertical velocity field (vd) | */ - GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY=32, /* ignore speed accuracy field | */ - GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY=64, /* ignore horizontal accuracy field | */ - GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY=128, /* ignore vertical accuracy field | */ - GPS_INPUT_IGNORE_FLAGS_ENUM_END=129, /* | */ -} GPS_INPUT_IGNORE_FLAGS; -#endif - -/** @brief Possible actions an aircraft can take to avoid a collision. */ -#ifndef HAVE_ENUM_MAV_COLLISION_ACTION -#define HAVE_ENUM_MAV_COLLISION_ACTION -typedef enum MAV_COLLISION_ACTION -{ - MAV_COLLISION_ACTION_NONE=0, /* Ignore any potential collisions | */ - MAV_COLLISION_ACTION_REPORT=1, /* Report potential collision | */ - MAV_COLLISION_ACTION_ASCEND_OR_DESCEND=2, /* Ascend or Descend to avoid threat | */ - MAV_COLLISION_ACTION_MOVE_HORIZONTALLY=3, /* Move horizontally to avoid threat | */ - MAV_COLLISION_ACTION_MOVE_PERPENDICULAR=4, /* Aircraft to move perpendicular to the collision's velocity vector | */ - MAV_COLLISION_ACTION_RTL=5, /* Aircraft to fly directly back to its launch point | */ - MAV_COLLISION_ACTION_HOVER=6, /* Aircraft to stop in place | */ - MAV_COLLISION_ACTION_ENUM_END=7, /* | */ -} MAV_COLLISION_ACTION; -#endif - -/** @brief Aircraft-rated danger from this threat. */ -#ifndef HAVE_ENUM_MAV_COLLISION_THREAT_LEVEL -#define HAVE_ENUM_MAV_COLLISION_THREAT_LEVEL -typedef enum MAV_COLLISION_THREAT_LEVEL -{ - MAV_COLLISION_THREAT_LEVEL_NONE=0, /* Not a threat | */ - MAV_COLLISION_THREAT_LEVEL_LOW=1, /* Craft is mildly concerned about this threat | */ - MAV_COLLISION_THREAT_LEVEL_HIGH=2, /* Craft is panicing, and may take actions to avoid threat | */ - MAV_COLLISION_THREAT_LEVEL_ENUM_END=3, /* | */ -} MAV_COLLISION_THREAT_LEVEL; -#endif - -/** @brief Source of information about this collision. */ -#ifndef HAVE_ENUM_MAV_COLLISION_SRC -#define HAVE_ENUM_MAV_COLLISION_SRC -typedef enum MAV_COLLISION_SRC -{ - MAV_COLLISION_SRC_ADSB=0, /* ID field references ADSB_VEHICLE packets | */ - MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT=1, /* ID field references MAVLink SRC ID | */ - MAV_COLLISION_SRC_ENUM_END=2, /* | */ -} MAV_COLLISION_SRC; -#endif - -/** @brief Type of GPS fix */ -#ifndef HAVE_ENUM_GPS_FIX_TYPE -#define HAVE_ENUM_GPS_FIX_TYPE -typedef enum GPS_FIX_TYPE -{ - GPS_FIX_TYPE_NO_GPS=0, /* No GPS connected | */ - GPS_FIX_TYPE_NO_FIX=1, /* No position information, GPS is connected | */ - GPS_FIX_TYPE_2D_FIX=2, /* 2D position | */ - GPS_FIX_TYPE_3D_FIX=3, /* 3D position | */ - GPS_FIX_TYPE_DGPS=4, /* DGPS/SBAS aided 3D position | */ - GPS_FIX_TYPE_RTK_FLOAT=5, /* RTK float, 3D position | */ - GPS_FIX_TYPE_RTK_FIXED=6, /* RTK Fixed, 3D position | */ - GPS_FIX_TYPE_STATIC=7, /* Static fixed, typically used for base stations | */ - GPS_FIX_TYPE_ENUM_END=8, /* | */ -} GPS_FIX_TYPE; -#endif - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_heartbeat.h" -#include "./mavlink_msg_sys_status.h" -#include "./mavlink_msg_system_time.h" -#include "./mavlink_msg_ping.h" -#include "./mavlink_msg_change_operator_control.h" -#include "./mavlink_msg_change_operator_control_ack.h" -#include "./mavlink_msg_auth_key.h" -#include "./mavlink_msg_set_mode.h" -#include "./mavlink_msg_param_request_read.h" -#include "./mavlink_msg_param_request_list.h" -#include "./mavlink_msg_param_value.h" -#include "./mavlink_msg_param_set.h" -#include "./mavlink_msg_gps_raw_int.h" -#include "./mavlink_msg_gps_status.h" -#include "./mavlink_msg_scaled_imu.h" -#include "./mavlink_msg_raw_imu.h" -#include "./mavlink_msg_raw_pressure.h" -#include "./mavlink_msg_scaled_pressure.h" -#include "./mavlink_msg_attitude.h" -#include "./mavlink_msg_attitude_quaternion.h" -#include "./mavlink_msg_local_position_ned.h" -#include "./mavlink_msg_global_position_int.h" -#include "./mavlink_msg_rc_channels_scaled.h" -#include "./mavlink_msg_rc_channels_raw.h" -#include "./mavlink_msg_servo_output_raw.h" -#include "./mavlink_msg_mission_request_partial_list.h" -#include "./mavlink_msg_mission_write_partial_list.h" -#include "./mavlink_msg_mission_item.h" -#include "./mavlink_msg_mission_request.h" -#include "./mavlink_msg_mission_set_current.h" -#include "./mavlink_msg_mission_current.h" -#include "./mavlink_msg_mission_request_list.h" -#include "./mavlink_msg_mission_count.h" -#include "./mavlink_msg_mission_clear_all.h" -#include "./mavlink_msg_mission_item_reached.h" -#include "./mavlink_msg_mission_ack.h" -#include "./mavlink_msg_set_gps_global_origin.h" -#include "./mavlink_msg_gps_global_origin.h" -#include "./mavlink_msg_param_map_rc.h" -#include "./mavlink_msg_mission_request_int.h" -#include "./mavlink_msg_safety_set_allowed_area.h" -#include "./mavlink_msg_safety_allowed_area.h" -#include "./mavlink_msg_attitude_quaternion_cov.h" -#include "./mavlink_msg_nav_controller_output.h" -#include "./mavlink_msg_global_position_int_cov.h" -#include "./mavlink_msg_local_position_ned_cov.h" -#include "./mavlink_msg_rc_channels.h" -#include "./mavlink_msg_request_data_stream.h" -#include "./mavlink_msg_data_stream.h" -#include "./mavlink_msg_manual_control.h" -#include "./mavlink_msg_rc_channels_override.h" -#include "./mavlink_msg_mission_item_int.h" -#include "./mavlink_msg_vfr_hud.h" -#include "./mavlink_msg_command_int.h" -#include "./mavlink_msg_command_long.h" -#include "./mavlink_msg_command_ack.h" -#include "./mavlink_msg_manual_setpoint.h" -#include "./mavlink_msg_set_attitude_target.h" -#include "./mavlink_msg_attitude_target.h" -#include "./mavlink_msg_set_position_target_local_ned.h" -#include "./mavlink_msg_position_target_local_ned.h" -#include "./mavlink_msg_set_position_target_global_int.h" -#include "./mavlink_msg_position_target_global_int.h" -#include "./mavlink_msg_local_position_ned_system_global_offset.h" -#include "./mavlink_msg_hil_state.h" -#include "./mavlink_msg_hil_controls.h" -#include "./mavlink_msg_hil_rc_inputs_raw.h" -#include "./mavlink_msg_hil_actuator_controls.h" -#include "./mavlink_msg_optical_flow.h" -#include "./mavlink_msg_global_vision_position_estimate.h" -#include "./mavlink_msg_vision_position_estimate.h" -#include "./mavlink_msg_vision_speed_estimate.h" -#include "./mavlink_msg_vicon_position_estimate.h" -#include "./mavlink_msg_highres_imu.h" -#include "./mavlink_msg_optical_flow_rad.h" -#include "./mavlink_msg_hil_sensor.h" -#include "./mavlink_msg_sim_state.h" -#include "./mavlink_msg_radio_status.h" -#include "./mavlink_msg_file_transfer_protocol.h" -#include "./mavlink_msg_timesync.h" -#include "./mavlink_msg_camera_trigger.h" -#include "./mavlink_msg_hil_gps.h" -#include "./mavlink_msg_hil_optical_flow.h" -#include "./mavlink_msg_hil_state_quaternion.h" -#include "./mavlink_msg_scaled_imu2.h" -#include "./mavlink_msg_log_request_list.h" -#include "./mavlink_msg_log_entry.h" -#include "./mavlink_msg_log_request_data.h" -#include "./mavlink_msg_log_data.h" -#include "./mavlink_msg_log_erase.h" -#include "./mavlink_msg_log_request_end.h" -#include "./mavlink_msg_gps_inject_data.h" -#include "./mavlink_msg_gps2_raw.h" -#include "./mavlink_msg_power_status.h" -#include "./mavlink_msg_serial_control.h" -#include "./mavlink_msg_gps_rtk.h" -#include "./mavlink_msg_gps2_rtk.h" -#include "./mavlink_msg_scaled_imu3.h" -#include "./mavlink_msg_data_transmission_handshake.h" -#include "./mavlink_msg_encapsulated_data.h" -#include "./mavlink_msg_distance_sensor.h" -#include "./mavlink_msg_terrain_request.h" -#include "./mavlink_msg_terrain_data.h" -#include "./mavlink_msg_terrain_check.h" -#include "./mavlink_msg_terrain_report.h" -#include "./mavlink_msg_scaled_pressure2.h" -#include "./mavlink_msg_att_pos_mocap.h" -#include "./mavlink_msg_set_actuator_control_target.h" -#include "./mavlink_msg_actuator_control_target.h" -#include "./mavlink_msg_altitude.h" -#include "./mavlink_msg_resource_request.h" -#include "./mavlink_msg_scaled_pressure3.h" -#include "./mavlink_msg_follow_target.h" -#include "./mavlink_msg_control_system_state.h" -#include "./mavlink_msg_battery_status.h" -#include "./mavlink_msg_autopilot_version.h" -#include "./mavlink_msg_landing_target.h" -#include "./mavlink_msg_estimator_status.h" -#include "./mavlink_msg_wind_cov.h" -#include "./mavlink_msg_gps_input.h" -#include "./mavlink_msg_gps_rtcm_data.h" -#include "./mavlink_msg_high_latency.h" -#include "./mavlink_msg_vibration.h" -#include "./mavlink_msg_home_position.h" -#include "./mavlink_msg_set_home_position.h" -#include "./mavlink_msg_message_interval.h" -#include "./mavlink_msg_extended_sys_state.h" -#include "./mavlink_msg_adsb_vehicle.h" -#include "./mavlink_msg_collision.h" -#include "./mavlink_msg_v2_extension.h" -#include "./mavlink_msg_memory_vect.h" -#include "./mavlink_msg_debug_vect.h" -#include "./mavlink_msg_named_value_float.h" -#include "./mavlink_msg_named_value_int.h" -#include "./mavlink_msg_statustext.h" -#include "./mavlink_msg_debug.h" - -// base include - - -#undef MAVLINK_THIS_XML_IDX -#define MAVLINK_THIS_XML_IDX 1 - -#if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX -# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, MAVLINK_MESSAGE_INFO_GPS_INPUT, MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA, MAVLINK_MESSAGE_INFO_HIGH_LATENCY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, MAVLINK_MESSAGE_INFO_COLLISION, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} -# if MAVLINK_COMMAND_24BIT -# include "../mavlink_get_info.h" -# endif -#endif - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // MAVLINK_COMMON_H diff --git a/include/mavlink/v1.0/common/mavlink.h b/include/mavlink/v1.0/common/mavlink.h deleted file mode 100644 index 6644aa5..0000000 --- a/include/mavlink/v1.0/common/mavlink.h +++ /dev/null @@ -1,34 +0,0 @@ -/** @file - * @brief MAVLink comm protocol built from common.xml - * @see http://mavlink.org - */ -#pragma once -#ifndef MAVLINK_H -#define MAVLINK_H - -#define MAVLINK_PRIMARY_XML_IDX 1 - -#ifndef MAVLINK_STX -#define MAVLINK_STX 254 -#endif - -#ifndef MAVLINK_ENDIAN -#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN -#endif - -#ifndef MAVLINK_ALIGNED_FIELDS -#define MAVLINK_ALIGNED_FIELDS 1 -#endif - -#ifndef MAVLINK_CRC_EXTRA -#define MAVLINK_CRC_EXTRA 1 -#endif - -#ifndef MAVLINK_COMMAND_24BIT -#define MAVLINK_COMMAND_24BIT 0 -#endif - -#include "version.h" -#include "common.h" - -#endif // MAVLINK_H diff --git a/include/mavlink/v1.0/common/mavlink_msg_actuator_control_target.h b/include/mavlink/v1.0/common/mavlink_msg_actuator_control_target.h deleted file mode 100644 index 2d1ebc0..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_actuator_control_target.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE ACTUATOR_CONTROL_TARGET PACKING - -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET 140 - -MAVPACKED( -typedef struct __mavlink_actuator_control_target_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ - uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ -}) mavlink_actuator_control_target_t; - -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41 -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN 41 -#define MAVLINK_MSG_ID_140_LEN 41 -#define MAVLINK_MSG_ID_140_MIN_LEN 41 - -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC 181 -#define MAVLINK_MSG_ID_140_CRC 181 - -#define MAVLINK_MSG_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \ - 140, \ - "ACTUATOR_CONTROL_TARGET", \ - 3, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \ - "ACTUATOR_CONTROL_TARGET", \ - 3, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ - } \ -} -#endif - -/** - * @brief Pack a actuator_control_target 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 (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t group_mlx, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Pack a actuator_control_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t group_mlx,const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Encode a actuator_control_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) -{ - return mavlink_msg_actuator_control_target_pack(system_id, component_id, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); -} - -/** - * @brief Encode a actuator_control_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) -{ - return mavlink_msg_actuator_control_target_pack_chan(system_id, component_id, chan, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); -} - -/** - * @brief Send a actuator_control_target message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -/** - * @brief Send a actuator_control_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_actuator_control_target_send_struct(mavlink_channel_t chan, const mavlink_actuator_control_target_t* actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_actuator_control_target_send(chan, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)actuator_control_target, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_actuator_control_target_t *packet = (mavlink_actuator_control_target_t *)msgbuf; - packet->time_usec = time_usec; - packet->group_mlx = group_mlx; - mav_array_memcpy(packet->controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ACTUATOR_CONTROL_TARGET UNPACKING - - -/** - * @brief Get field time_usec from actuator_control_target message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field group_mlx from actuator_control_target message - * - * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - */ -static inline uint8_t mavlink_msg_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field controls from actuator_control_target message - * - * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -static inline uint16_t mavlink_msg_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) -{ - return _MAV_RETURN_float_array(msg, controls, 8, 8); -} - -/** - * @brief Decode a actuator_control_target message into a struct - * - * @param msg The message to decode - * @param actuator_control_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_actuator_control_target_t* actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - actuator_control_target->time_usec = mavlink_msg_actuator_control_target_get_time_usec(msg); - mavlink_msg_actuator_control_target_get_controls(msg, actuator_control_target->controls); - actuator_control_target->group_mlx = mavlink_msg_actuator_control_target_get_group_mlx(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN? msg->len : MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN; - memset(actuator_control_target, 0, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); - memcpy(actuator_control_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_adsb_vehicle.h b/include/mavlink/v1.0/common/mavlink_msg_adsb_vehicle.h deleted file mode 100644 index d395be5..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_adsb_vehicle.h +++ /dev/null @@ -1,505 +0,0 @@ -#pragma once -// MESSAGE ADSB_VEHICLE PACKING - -#define MAVLINK_MSG_ID_ADSB_VEHICLE 246 - -MAVPACKED( -typedef struct __mavlink_adsb_vehicle_t { - uint32_t ICAO_address; /*< ICAO address*/ - int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ - int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ - int32_t altitude; /*< Altitude(ASL) in millimeters*/ - uint16_t heading; /*< Course over ground in centidegrees*/ - uint16_t hor_velocity; /*< The horizontal velocity in centimeters/second*/ - int16_t ver_velocity; /*< The vertical velocity in centimeters/second, positive is up*/ - uint16_t flags; /*< Flags to indicate various statuses including valid data fields*/ - uint16_t squawk; /*< Squawk code*/ - uint8_t altitude_type; /*< Type from ADSB_ALTITUDE_TYPE enum*/ - char callsign[9]; /*< The callsign, 8+null*/ - uint8_t emitter_type; /*< Type from ADSB_EMITTER_TYPE enum*/ - uint8_t tslc; /*< Time since last communication in seconds*/ -}) mavlink_adsb_vehicle_t; - -#define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN 38 -#define MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN 38 -#define MAVLINK_MSG_ID_246_LEN 38 -#define MAVLINK_MSG_ID_246_MIN_LEN 38 - -#define MAVLINK_MSG_ID_ADSB_VEHICLE_CRC 184 -#define MAVLINK_MSG_ID_246_CRC 184 - -#define MAVLINK_MSG_ADSB_VEHICLE_FIELD_CALLSIGN_LEN 9 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE { \ - 246, \ - "ADSB_VEHICLE", \ - 13, \ - { { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \ - { "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \ - { "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ - { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ - { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ - { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \ - { "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \ - { "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE { \ - "ADSB_VEHICLE", \ - 13, \ - { { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \ - { "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \ - { "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ - { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ - { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ - { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \ - { "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \ - { "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \ - } \ -} -#endif - -/** - * @brief Pack a adsb_vehicle 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 ICAO_address ICAO address - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum - * @param altitude Altitude(ASL) in millimeters - * @param heading Course over ground in centidegrees - * @param hor_velocity The horizontal velocity in centimeters/second - * @param ver_velocity The vertical velocity in centimeters/second, positive is up - * @param callsign The callsign, 8+null - * @param emitter_type Type from ADSB_EMITTER_TYPE enum - * @param tslc Time since last communication in seconds - * @param flags Flags to indicate various statuses including valid data fields - * @param squawk Squawk code - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_adsb_vehicle_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#else - mavlink_adsb_vehicle_t packet; - packet.ICAO_address = ICAO_address; - packet.lat = lat; - packet.lon = lon; - packet.altitude = altitude; - packet.heading = heading; - packet.hor_velocity = hor_velocity; - packet.ver_velocity = ver_velocity; - packet.flags = flags; - packet.squawk = squawk; - packet.altitude_type = altitude_type; - packet.emitter_type = emitter_type; - packet.tslc = tslc; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -} - -/** - * @brief Pack a adsb_vehicle message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ICAO_address ICAO address - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum - * @param altitude Altitude(ASL) in millimeters - * @param heading Course over ground in centidegrees - * @param hor_velocity The horizontal velocity in centimeters/second - * @param ver_velocity The vertical velocity in centimeters/second, positive is up - * @param callsign The callsign, 8+null - * @param emitter_type Type from ADSB_EMITTER_TYPE enum - * @param tslc Time since last communication in seconds - * @param flags Flags to indicate various statuses including valid data fields - * @param squawk Squawk code - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_adsb_vehicle_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t ICAO_address,int32_t lat,int32_t lon,uint8_t altitude_type,int32_t altitude,uint16_t heading,uint16_t hor_velocity,int16_t ver_velocity,const char *callsign,uint8_t emitter_type,uint8_t tslc,uint16_t flags,uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#else - mavlink_adsb_vehicle_t packet; - packet.ICAO_address = ICAO_address; - packet.lat = lat; - packet.lon = lon; - packet.altitude = altitude; - packet.heading = heading; - packet.hor_velocity = hor_velocity; - packet.ver_velocity = ver_velocity; - packet.flags = flags; - packet.squawk = squawk; - packet.altitude_type = altitude_type; - packet.emitter_type = emitter_type; - packet.tslc = tslc; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -} - -/** - * @brief Encode a adsb_vehicle struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param adsb_vehicle C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_adsb_vehicle_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle) -{ - return mavlink_msg_adsb_vehicle_pack(system_id, component_id, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); -} - -/** - * @brief Encode a adsb_vehicle struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param adsb_vehicle C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_adsb_vehicle_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle) -{ - return mavlink_msg_adsb_vehicle_pack_chan(system_id, component_id, chan, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); -} - -/** - * @brief Send a adsb_vehicle message - * @param chan MAVLink channel to send the message - * - * @param ICAO_address ICAO address - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum - * @param altitude Altitude(ASL) in millimeters - * @param heading Course over ground in centidegrees - * @param hor_velocity The horizontal velocity in centimeters/second - * @param ver_velocity The vertical velocity in centimeters/second, positive is up - * @param callsign The callsign, 8+null - * @param emitter_type Type from ADSB_EMITTER_TYPE enum - * @param tslc Time since last communication in seconds - * @param flags Flags to indicate various statuses including valid data fields - * @param squawk Squawk code - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_adsb_vehicle_send(mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#else - mavlink_adsb_vehicle_t packet; - packet.ICAO_address = ICAO_address; - packet.lat = lat; - packet.lon = lon; - packet.altitude = altitude; - packet.heading = heading; - packet.hor_velocity = hor_velocity; - packet.ver_velocity = ver_velocity; - packet.flags = flags; - packet.squawk = squawk; - packet.altitude_type = altitude_type; - packet.emitter_type = emitter_type; - packet.tslc = tslc; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)&packet, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#endif -} - -/** - * @brief Send a adsb_vehicle message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_adsb_vehicle_send_struct(mavlink_channel_t chan, const mavlink_adsb_vehicle_t* adsb_vehicle) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_adsb_vehicle_send(chan, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)adsb_vehicle, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ADSB_VEHICLE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_adsb_vehicle_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#else - mavlink_adsb_vehicle_t *packet = (mavlink_adsb_vehicle_t *)msgbuf; - packet->ICAO_address = ICAO_address; - packet->lat = lat; - packet->lon = lon; - packet->altitude = altitude; - packet->heading = heading; - packet->hor_velocity = hor_velocity; - packet->ver_velocity = ver_velocity; - packet->flags = flags; - packet->squawk = squawk; - packet->altitude_type = altitude_type; - packet->emitter_type = emitter_type; - packet->tslc = tslc; - mav_array_memcpy(packet->callsign, callsign, sizeof(char)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)packet, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ADSB_VEHICLE UNPACKING - - -/** - * @brief Get field ICAO_address from adsb_vehicle message - * - * @return ICAO address - */ -static inline uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field lat from adsb_vehicle message - * - * @return Latitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_adsb_vehicle_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon from adsb_vehicle message - * - * @return Longitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_adsb_vehicle_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field altitude_type from adsb_vehicle message - * - * @return Type from ADSB_ALTITUDE_TYPE enum - */ -static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field altitude from adsb_vehicle message - * - * @return Altitude(ASL) in millimeters - */ -static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field heading from adsb_vehicle message - * - * @return Course over ground in centidegrees - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field hor_velocity from adsb_vehicle message - * - * @return The horizontal velocity in centimeters/second - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field ver_velocity from adsb_vehicle message - * - * @return The vertical velocity in centimeters/second, positive is up - */ -static inline int16_t mavlink_msg_adsb_vehicle_get_ver_velocity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field callsign from adsb_vehicle message - * - * @return The callsign, 8+null - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_callsign(const mavlink_message_t* msg, char *callsign) -{ - return _MAV_RETURN_char_array(msg, callsign, 9, 27); -} - -/** - * @brief Get field emitter_type from adsb_vehicle message - * - * @return Type from ADSB_EMITTER_TYPE enum - */ -static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field tslc from adsb_vehicle message - * - * @return Time since last communication in seconds - */ -static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 37); -} - -/** - * @brief Get field flags from adsb_vehicle message - * - * @return Flags to indicate various statuses including valid data fields - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field squawk from adsb_vehicle message - * - * @return Squawk code - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_squawk(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Decode a adsb_vehicle message into a struct - * - * @param msg The message to decode - * @param adsb_vehicle C-struct to decode the message contents into - */ -static inline void mavlink_msg_adsb_vehicle_decode(const mavlink_message_t* msg, mavlink_adsb_vehicle_t* adsb_vehicle) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - adsb_vehicle->ICAO_address = mavlink_msg_adsb_vehicle_get_ICAO_address(msg); - adsb_vehicle->lat = mavlink_msg_adsb_vehicle_get_lat(msg); - adsb_vehicle->lon = mavlink_msg_adsb_vehicle_get_lon(msg); - adsb_vehicle->altitude = mavlink_msg_adsb_vehicle_get_altitude(msg); - adsb_vehicle->heading = mavlink_msg_adsb_vehicle_get_heading(msg); - adsb_vehicle->hor_velocity = mavlink_msg_adsb_vehicle_get_hor_velocity(msg); - adsb_vehicle->ver_velocity = mavlink_msg_adsb_vehicle_get_ver_velocity(msg); - adsb_vehicle->flags = mavlink_msg_adsb_vehicle_get_flags(msg); - adsb_vehicle->squawk = mavlink_msg_adsb_vehicle_get_squawk(msg); - adsb_vehicle->altitude_type = mavlink_msg_adsb_vehicle_get_altitude_type(msg); - mavlink_msg_adsb_vehicle_get_callsign(msg, adsb_vehicle->callsign); - adsb_vehicle->emitter_type = mavlink_msg_adsb_vehicle_get_emitter_type(msg); - adsb_vehicle->tslc = mavlink_msg_adsb_vehicle_get_tslc(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ADSB_VEHICLE_LEN? msg->len : MAVLINK_MSG_ID_ADSB_VEHICLE_LEN; - memset(adsb_vehicle, 0, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); - memcpy(adsb_vehicle, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_altitude.h b/include/mavlink/v1.0/common/mavlink_msg_altitude.h deleted file mode 100644 index d51a9e8..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_altitude.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE ALTITUDE PACKING - -#define MAVLINK_MSG_ID_ALTITUDE 141 - -MAVPACKED( -typedef struct __mavlink_altitude_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float altitude_monotonic; /*< This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.*/ - float altitude_amsl; /*< This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.*/ - float altitude_local; /*< This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.*/ - float altitude_relative; /*< This is the altitude above the home position. It resets on each change of the current home position.*/ - float altitude_terrain; /*< This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.*/ - float bottom_clearance; /*< This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.*/ -}) mavlink_altitude_t; - -#define MAVLINK_MSG_ID_ALTITUDE_LEN 32 -#define MAVLINK_MSG_ID_ALTITUDE_MIN_LEN 32 -#define MAVLINK_MSG_ID_141_LEN 32 -#define MAVLINK_MSG_ID_141_MIN_LEN 32 - -#define MAVLINK_MSG_ID_ALTITUDE_CRC 47 -#define MAVLINK_MSG_ID_141_CRC 47 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ALTITUDE { \ - 141, \ - "ALTITUDE", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_altitude_t, time_usec) }, \ - { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_monotonic) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_amsl) }, \ - { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_local) }, \ - { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, altitude_relative) }, \ - { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_altitude_t, altitude_terrain) }, \ - { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_altitude_t, bottom_clearance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ALTITUDE { \ - "ALTITUDE", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_altitude_t, time_usec) }, \ - { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_monotonic) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_amsl) }, \ - { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_local) }, \ - { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, altitude_relative) }, \ - { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_altitude_t, altitude_terrain) }, \ - { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_altitude_t, bottom_clearance) }, \ - } \ -} -#endif - -/** - * @brief Pack a altitude 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 (micros since boot or Unix epoch) - * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN); -#else - mavlink_altitude_t packet; - packet.time_usec = time_usec; - packet.altitude_monotonic = altitude_monotonic; - packet.altitude_amsl = altitude_amsl; - packet.altitude_local = altitude_local; - packet.altitude_relative = altitude_relative; - packet.altitude_terrain = altitude_terrain; - packet.bottom_clearance = bottom_clearance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ALTITUDE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -} - -/** - * @brief Pack a altitude message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN); -#else - mavlink_altitude_t packet; - packet.time_usec = time_usec; - packet.altitude_monotonic = altitude_monotonic; - packet.altitude_amsl = altitude_amsl; - packet.altitude_local = altitude_local; - packet.altitude_relative = altitude_relative; - packet.altitude_terrain = altitude_terrain; - packet.bottom_clearance = bottom_clearance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ALTITUDE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -} - -/** - * @brief Encode a altitude struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param altitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_altitude_t* altitude) -{ - return mavlink_msg_altitude_pack(system_id, component_id, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); -} - -/** - * @brief Encode a altitude struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param altitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_altitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_altitude_t* altitude) -{ - return mavlink_msg_altitude_pack_chan(system_id, component_id, chan, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); -} - -/** - * @brief Send a altitude message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_altitude_send(mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#else - mavlink_altitude_t packet; - packet.time_usec = time_usec; - packet.altitude_monotonic = altitude_monotonic; - packet.altitude_amsl = altitude_amsl; - packet.altitude_local = altitude_local; - packet.altitude_relative = altitude_relative; - packet.altitude_terrain = altitude_terrain; - packet.bottom_clearance = bottom_clearance; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#endif -} - -/** - * @brief Send a altitude message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_altitude_send_struct(mavlink_channel_t chan, const mavlink_altitude_t* altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_altitude_send(chan, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)altitude, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ALTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_altitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#else - mavlink_altitude_t *packet = (mavlink_altitude_t *)msgbuf; - packet->time_usec = time_usec; - packet->altitude_monotonic = altitude_monotonic; - packet->altitude_amsl = altitude_amsl; - packet->altitude_local = altitude_local; - packet->altitude_relative = altitude_relative; - packet->altitude_terrain = altitude_terrain; - packet->bottom_clearance = bottom_clearance; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ALTITUDE UNPACKING - - -/** - * @brief Get field time_usec from altitude message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_altitude_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field altitude_monotonic from altitude message - * - * @return This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - */ -static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field altitude_amsl from altitude message - * - * @return This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - */ -static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field altitude_local from altitude message - * - * @return This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - */ -static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field altitude_relative from altitude message - * - * @return This is the altitude above the home position. It resets on each change of the current home position. - */ -static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field altitude_terrain from altitude message - * - * @return This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - */ -static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field bottom_clearance from altitude message - * - * @return This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - */ -static inline float mavlink_msg_altitude_get_bottom_clearance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a altitude message into a struct - * - * @param msg The message to decode - * @param altitude C-struct to decode the message contents into - */ -static inline void mavlink_msg_altitude_decode(const mavlink_message_t* msg, mavlink_altitude_t* altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - altitude->time_usec = mavlink_msg_altitude_get_time_usec(msg); - altitude->altitude_monotonic = mavlink_msg_altitude_get_altitude_monotonic(msg); - altitude->altitude_amsl = mavlink_msg_altitude_get_altitude_amsl(msg); - altitude->altitude_local = mavlink_msg_altitude_get_altitude_local(msg); - altitude->altitude_relative = mavlink_msg_altitude_get_altitude_relative(msg); - altitude->altitude_terrain = mavlink_msg_altitude_get_altitude_terrain(msg); - altitude->bottom_clearance = mavlink_msg_altitude_get_bottom_clearance(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ALTITUDE_LEN? msg->len : MAVLINK_MSG_ID_ALTITUDE_LEN; - memset(altitude, 0, MAVLINK_MSG_ID_ALTITUDE_LEN); - memcpy(altitude, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_att_pos_mocap.h b/include/mavlink/v1.0/common/mavlink_msg_att_pos_mocap.h deleted file mode 100644 index 3c1a251..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_att_pos_mocap.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE ATT_POS_MOCAP PACKING - -#define MAVLINK_MSG_ID_ATT_POS_MOCAP 138 - -MAVPACKED( -typedef struct __mavlink_att_pos_mocap_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float x; /*< X position in meters (NED)*/ - float y; /*< Y position in meters (NED)*/ - float z; /*< Z position in meters (NED)*/ -}) mavlink_att_pos_mocap_t; - -#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36 -#define MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN 36 -#define MAVLINK_MSG_ID_138_LEN 36 -#define MAVLINK_MSG_ID_138_MIN_LEN 36 - -#define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC 109 -#define MAVLINK_MSG_ID_138_CRC 109 - -#define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \ - 138, \ - "ATT_POS_MOCAP", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \ - "ATT_POS_MOCAP", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \ - } \ -} -#endif - -/** - * @brief Pack a att_pos_mocap 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 (micros since boot or Unix epoch) - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x X position in meters (NED) - * @param y Y position in meters (NED) - * @param z Z position in meters (NED) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *q, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#else - mavlink_att_pos_mocap_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -} - -/** - * @brief Pack a att_pos_mocap message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x X position in meters (NED) - * @param y Y position in meters (NED) - * @param z Z position in meters (NED) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *q,float x,float y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#else - mavlink_att_pos_mocap_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -} - -/** - * @brief Encode a att_pos_mocap struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param att_pos_mocap C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_att_pos_mocap_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap) -{ - return mavlink_msg_att_pos_mocap_pack(system_id, component_id, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z); -} - -/** - * @brief Encode a att_pos_mocap struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param att_pos_mocap C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap) -{ - return mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, chan, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z); -} - -/** - * @brief Send a att_pos_mocap message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x X position in meters (NED) - * @param y Y position in meters (NED) - * @param z Z position in meters (NED) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#else - mavlink_att_pos_mocap_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#endif -} - -/** - * @brief Send a att_pos_mocap message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_att_pos_mocap_send_struct(mavlink_channel_t chan, const mavlink_att_pos_mocap_t* att_pos_mocap) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_att_pos_mocap_send(chan, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)att_pos_mocap, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#else - mavlink_att_pos_mocap_t *packet = (mavlink_att_pos_mocap_t *)msgbuf; - packet->time_usec = time_usec; - packet->x = x; - packet->y = y; - packet->z = z; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATT_POS_MOCAP UNPACKING - - -/** - * @brief Get field time_usec from att_pos_mocap message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field q from att_pos_mocap message - * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 8); -} - -/** - * @brief Get field x from att_pos_mocap message - * - * @return X position in meters (NED) - */ -static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field y from att_pos_mocap message - * - * @return Y position in meters (NED) - */ -static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field z from att_pos_mocap message - * - * @return Z position in meters (NED) - */ -static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Decode a att_pos_mocap message into a struct - * - * @param msg The message to decode - * @param att_pos_mocap C-struct to decode the message contents into - */ -static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t* msg, mavlink_att_pos_mocap_t* att_pos_mocap) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - att_pos_mocap->time_usec = mavlink_msg_att_pos_mocap_get_time_usec(msg); - mavlink_msg_att_pos_mocap_get_q(msg, att_pos_mocap->q); - att_pos_mocap->x = mavlink_msg_att_pos_mocap_get_x(msg); - att_pos_mocap->y = mavlink_msg_att_pos_mocap_get_y(msg); - att_pos_mocap->z = mavlink_msg_att_pos_mocap_get_z(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN? msg->len : MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN; - memset(att_pos_mocap, 0, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); - memcpy(att_pos_mocap, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_attitude.h b/include/mavlink/v1.0/common/mavlink_msg_attitude.h deleted file mode 100644 index 21472fb..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_attitude.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE PACKING - -#define MAVLINK_MSG_ID_ATTITUDE 30 - -MAVPACKED( -typedef struct __mavlink_attitude_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float roll; /*< Roll angle (rad, -pi..+pi)*/ - float pitch; /*< Pitch angle (rad, -pi..+pi)*/ - float yaw; /*< Yaw angle (rad, -pi..+pi)*/ - float rollspeed; /*< Roll angular speed (rad/s)*/ - float pitchspeed; /*< Pitch angular speed (rad/s)*/ - float yawspeed; /*< Yaw angular speed (rad/s)*/ -}) mavlink_attitude_t; - -#define MAVLINK_MSG_ID_ATTITUDE_LEN 28 -#define MAVLINK_MSG_ID_ATTITUDE_MIN_LEN 28 -#define MAVLINK_MSG_ID_30_LEN 28 -#define MAVLINK_MSG_ID_30_MIN_LEN 28 - -#define MAVLINK_MSG_ID_ATTITUDE_CRC 39 -#define MAVLINK_MSG_ID_30_CRC 39 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE { \ - 30, \ - "ATTITUDE", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE { \ - "ATTITUDE", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude 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_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - 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, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -} - -/** - * @brief Pack a attitude message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - 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, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -} - -/** - * @brief Encode a attitude struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude) -{ - return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); -} - -/** - * @brief Encode a attitude struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_t* attitude) -{ - return mavlink_msg_attitude_pack_chan(system_id, component_id, chan, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); -} - -/** - * @brief Send a attitude message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#endif -} - -/** - * @brief Send a attitude message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_send_struct(mavlink_channel_t chan, const mavlink_attitude_t* attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_send(chan, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)attitude, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE UNPACKING - - -/** - * @brief Get field time_boot_ms from attitude message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll from attitude message - * - * @return Roll angle (rad, -pi..+pi) - */ -static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch from attitude message - * - * @return Pitch angle (rad, -pi..+pi) - */ -static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from attitude message - * - * @return Yaw angle (rad, -pi..+pi) - */ -static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field rollspeed from attitude message - * - * @return Roll angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitchspeed from attitude message - * - * @return Pitch angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yawspeed from attitude message - * - * @return Yaw angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a attitude message into a struct - * - * @param msg The message to decode - * @param attitude C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg); - attitude->roll = mavlink_msg_attitude_get_roll(msg); - attitude->pitch = mavlink_msg_attitude_get_pitch(msg); - attitude->yaw = mavlink_msg_attitude_get_yaw(msg); - attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg); - attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); - attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_LEN; - memset(attitude, 0, MAVLINK_MSG_ID_ATTITUDE_LEN); - memcpy(attitude, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h b/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h deleted file mode 100644 index df8e1e9..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE_QUATERNION PACKING - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 - -MAVPACKED( -typedef struct __mavlink_attitude_quaternion_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float q1; /*< Quaternion component 1, w (1 in null-rotation)*/ - float q2; /*< Quaternion component 2, x (0 in null-rotation)*/ - float q3; /*< Quaternion component 3, y (0 in null-rotation)*/ - float q4; /*< Quaternion component 4, z (0 in null-rotation)*/ - float rollspeed; /*< Roll angular speed (rad/s)*/ - float pitchspeed; /*< Pitch angular speed (rad/s)*/ - float yawspeed; /*< Yaw angular speed (rad/s)*/ -}) mavlink_attitude_quaternion_t; - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN 32 -#define MAVLINK_MSG_ID_31_LEN 32 -#define MAVLINK_MSG_ID_31_MIN_LEN 32 - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246 -#define MAVLINK_MSG_ID_31_CRC 246 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ - 31, \ - "ATTITUDE_QUATERNION", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ - { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ - "ATTITUDE_QUATERNION", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ - { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude_quaternion 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_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - - 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; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - 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, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -} - -/** - * @brief Pack a attitude_quaternion message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - - 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; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - 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, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -} - -/** - * @brief Encode a attitude_quaternion struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) -{ - return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); -} - -/** - * @brief Encode a attitude_quaternion struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) -{ - return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); -} - -/** - * @brief Send a attitude_quaternion message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - mavlink_attitude_quaternion_t packet; - packet.time_boot_ms = time_boot_ms; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#endif -} - -/** - * @brief Send a attitude_quaternion message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_quaternion_send_struct(mavlink_channel_t chan, const mavlink_attitude_quaternion_t* attitude_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_quaternion_send(chan, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)attitude_quaternion, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, q1); - _mav_put_float(buf, 8, q2); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->q1 = q1; - packet->q2 = q2; - packet->q3 = q3; - packet->q4 = q4; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE_QUATERNION UNPACKING - - -/** - * @brief Get field time_boot_ms from attitude_quaternion message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field q1 from attitude_quaternion message - * - * @return Quaternion component 1, w (1 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field q2 from attitude_quaternion message - * - * @return Quaternion component 2, x (0 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field q3 from attitude_quaternion message - * - * @return Quaternion component 3, y (0 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field q4 from attitude_quaternion message - * - * @return Quaternion component 4, z (0 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field rollspeed from attitude_quaternion message - * - * @return Roll angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitchspeed from attitude_quaternion message - * - * @return Pitch angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yawspeed from attitude_quaternion message - * - * @return Yaw angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a attitude_quaternion message into a struct - * - * @param msg The message to decode - * @param attitude_quaternion C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg); - attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg); - attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg); - attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg); - attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg); - attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg); - attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg); - attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN; - memset(attitude_quaternion, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); - memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion_cov.h b/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion_cov.h deleted file mode 100644 index adfcfa7..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion_cov.h +++ /dev/null @@ -1,331 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE_QUATERNION_COV PACKING - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61 - -MAVPACKED( -typedef struct __mavlink_attitude_quaternion_cov_t { - uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/ - float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/ - float rollspeed; /*< Roll angular speed (rad/s)*/ - float pitchspeed; /*< Pitch angular speed (rad/s)*/ - float yawspeed; /*< Yaw angular speed (rad/s)*/ - float covariance[9]; /*< Attitude covariance*/ -}) mavlink_attitude_quaternion_cov_t; - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 72 -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN 72 -#define MAVLINK_MSG_ID_61_LEN 72 -#define MAVLINK_MSG_ID_61_MIN_LEN 72 - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC 167 -#define MAVLINK_MSG_ID_61_CRC 167 - -#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN 4 -#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN 9 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \ - 61, \ - "ATTITUDE_QUATERNION_COV", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 36, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \ - "ATTITUDE_QUATERNION_COV", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 36, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude_quaternion_cov 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 since system boot or since UNIX epoch) - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @param covariance Attitude covariance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#else - mavlink_attitude_quaternion_cov_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -} - -/** - * @brief Pack a attitude_quaternion_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @param covariance Attitude covariance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *q,float rollspeed,float pitchspeed,float yawspeed,const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#else - mavlink_attitude_quaternion_cov_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -} - -/** - * @brief Encode a attitude_quaternion_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ - return mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, msg, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); -} - -/** - * @brief Encode a attitude_quaternion_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ - return mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, chan, msg, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); -} - -/** - * @brief Send a attitude_quaternion_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @param covariance Attitude covariance - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_attitude_quaternion_cov_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#else - mavlink_attitude_quaternion_cov_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#endif -} - -/** - * @brief Send a attitude_quaternion_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_quaternion_cov_send_struct(mavlink_channel_t chan, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_quaternion_cov_send(chan, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)attitude_quaternion_cov, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#else - mavlink_attitude_quaternion_cov_t *packet = (mavlink_attitude_quaternion_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE_QUATERNION_COV UNPACKING - - -/** - * @brief Get field time_usec from attitude_quaternion_cov message - * - * @return Timestamp (microseconds since system boot or since UNIX epoch) - */ -static inline uint64_t mavlink_msg_attitude_quaternion_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field q from attitude_quaternion_cov message - * - * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 8); -} - -/** - * @brief Get field rollspeed from attitude_quaternion_cov message - * - * @return Roll angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field pitchspeed from attitude_quaternion_cov message - * - * @return Pitch angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field yawspeed from attitude_quaternion_cov message - * - * @return Yaw angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field covariance from attitude_quaternion_cov message - * - * @return Attitude covariance - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 9, 36); -} - -/** - * @brief Decode a attitude_quaternion_cov message into a struct - * - * @param msg The message to decode - * @param attitude_quaternion_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_quaternion_cov_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude_quaternion_cov->time_usec = mavlink_msg_attitude_quaternion_cov_get_time_usec(msg); - mavlink_msg_attitude_quaternion_cov_get_q(msg, attitude_quaternion_cov->q); - attitude_quaternion_cov->rollspeed = mavlink_msg_attitude_quaternion_cov_get_rollspeed(msg); - attitude_quaternion_cov->pitchspeed = mavlink_msg_attitude_quaternion_cov_get_pitchspeed(msg); - attitude_quaternion_cov->yawspeed = mavlink_msg_attitude_quaternion_cov_get_yawspeed(msg); - mavlink_msg_attitude_quaternion_cov_get_covariance(msg, attitude_quaternion_cov->covariance); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN; - memset(attitude_quaternion_cov, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); - memcpy(attitude_quaternion_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_attitude_target.h b/include/mavlink/v1.0/common/mavlink_msg_attitude_target.h deleted file mode 100644 index a310920..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_attitude_target.h +++ /dev/null @@ -1,355 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE_TARGET PACKING - -#define MAVLINK_MSG_ID_ATTITUDE_TARGET 83 - -MAVPACKED( -typedef struct __mavlink_attitude_target_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float body_roll_rate; /*< Body roll rate in radians per second*/ - float body_pitch_rate; /*< Body pitch rate in radians per second*/ - float body_yaw_rate; /*< Body yaw rate in radians per second*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ - uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude*/ -}) mavlink_attitude_target_t; - -#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37 -#define MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN 37 -#define MAVLINK_MSG_ID_83_LEN 37 -#define MAVLINK_MSG_ID_83_MIN_LEN 37 - -#define MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22 -#define MAVLINK_MSG_ID_83_CRC 22 - -#define MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \ - 83, \ - "ATTITUDE_TARGET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \ - "ATTITUDE_TARGET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude_target 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_boot_ms Timestamp in milliseconds since system boot - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body pitch rate in radians per second - * @param body_yaw_rate Body yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#else - mavlink_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Pack a attitude_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body pitch rate in radians per second - * @param body_yaw_rate Body yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#else - mavlink_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Encode a attitude_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target) -{ - return mavlink_msg_attitude_target_pack(system_id, component_id, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); -} - -/** - * @brief Encode a attitude_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target) -{ - return mavlink_msg_attitude_target_pack_chan(system_id, component_id, chan, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); -} - -/** - * @brief Send a attitude_target message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body pitch rate in radians per second - * @param body_yaw_rate Body yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#else - mavlink_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#endif -} - -/** - * @brief Send a attitude_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_target_send_struct(mavlink_channel_t chan, const mavlink_attitude_target_t* attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_target_send(chan, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)attitude_target, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#else - mavlink_attitude_target_t *packet = (mavlink_attitude_target_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->body_roll_rate = body_roll_rate; - packet->body_pitch_rate = body_pitch_rate; - packet->body_yaw_rate = body_yaw_rate; - packet->thrust = thrust; - packet->type_mask = type_mask; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE_TARGET UNPACKING - - -/** - * @brief Get field time_boot_ms from attitude_target message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field type_mask from attitude_target message - * - * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - */ -static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field q from attitude_target message - * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 4); -} - -/** - * @brief Get field body_roll_rate from attitude_target message - * - * @return Body roll rate in radians per second - */ -static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field body_pitch_rate from attitude_target message - * - * @return Body pitch rate in radians per second - */ -static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field body_yaw_rate from attitude_target message - * - * @return Body yaw rate in radians per second - */ -static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field thrust from attitude_target message - * - * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - */ -static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Decode a attitude_target message into a struct - * - * @param msg The message to decode - * @param attitude_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_target_decode(const mavlink_message_t* msg, mavlink_attitude_target_t* attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude_target->time_boot_ms = mavlink_msg_attitude_target_get_time_boot_ms(msg); - mavlink_msg_attitude_target_get_q(msg, attitude_target->q); - attitude_target->body_roll_rate = mavlink_msg_attitude_target_get_body_roll_rate(msg); - attitude_target->body_pitch_rate = mavlink_msg_attitude_target_get_body_pitch_rate(msg); - attitude_target->body_yaw_rate = mavlink_msg_attitude_target_get_body_yaw_rate(msg); - attitude_target->thrust = mavlink_msg_attitude_target_get_thrust(msg); - attitude_target->type_mask = mavlink_msg_attitude_target_get_type_mask(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN; - memset(attitude_target, 0, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); - memcpy(attitude_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_auth_key.h b/include/mavlink/v1.0/common/mavlink_msg_auth_key.h deleted file mode 100644 index 2754a2a..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_auth_key.h +++ /dev/null @@ -1,213 +0,0 @@ -#pragma once -// MESSAGE AUTH_KEY PACKING - -#define MAVLINK_MSG_ID_AUTH_KEY 7 - -MAVPACKED( -typedef struct __mavlink_auth_key_t { - char key[32]; /*< key*/ -}) mavlink_auth_key_t; - -#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 -#define MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN 32 -#define MAVLINK_MSG_ID_7_LEN 32 -#define MAVLINK_MSG_ID_7_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ - 7, \ - "AUTH_KEY", \ - 1, \ - { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ - "AUTH_KEY", \ - 1, \ - { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ - } \ -} -#endif - -/** - * @brief Pack a auth_key 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 key key - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; - - _mav_put_char_array(buf, 0, key, 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, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -} - -/** - * @brief Pack a auth_key message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param key key - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; - - _mav_put_char_array(buf, 0, key, 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, 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, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -} - -/** - * @brief Encode a auth_key struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param auth_key C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) -{ - return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key); -} - -/** - * @brief Encode a auth_key struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param auth_key C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) -{ - return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key); -} - -/** - * @brief Send a auth_key message - * @param chan MAVLink channel to send the message - * - * @param key key - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#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, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#endif -} - -/** - * @brief Send a auth_key message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_auth_key_send_struct(mavlink_channel_t chan, const mavlink_auth_key_t* auth_key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_auth_key_send(chan, auth_key->key); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)auth_key, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_char_array(buf, 0, key, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#else - mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf; - - mav_array_memcpy(packet->key, key, sizeof(char)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE AUTH_KEY UNPACKING - - -/** - * @brief Get field key from auth_key message - * - * @return key - */ -static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key) -{ - return _MAV_RETURN_char_array(msg, key, 32, 0); -} - -/** - * @brief Decode a auth_key message into a struct - * - * @param msg The message to decode - * @param auth_key C-struct to decode the message contents into - */ -static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_auth_key_get_key(msg, auth_key->key); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_AUTH_KEY_LEN? msg->len : MAVLINK_MSG_ID_AUTH_KEY_LEN; - memset(auth_key, 0, MAVLINK_MSG_ID_AUTH_KEY_LEN); - memcpy(auth_key, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_autopilot_version.h b/include/mavlink/v1.0/common/mavlink_msg_autopilot_version.h deleted file mode 100644 index 68f7d83..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_autopilot_version.h +++ /dev/null @@ -1,457 +0,0 @@ -#pragma once -// MESSAGE AUTOPILOT_VERSION PACKING - -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148 - -MAVPACKED( -typedef struct __mavlink_autopilot_version_t { - uint64_t capabilities; /*< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)*/ - uint64_t uid; /*< UID if provided by hardware*/ - uint32_t flight_sw_version; /*< Firmware version number*/ - uint32_t middleware_sw_version; /*< Middleware version number*/ - uint32_t os_sw_version; /*< Operating system version number*/ - uint32_t board_version; /*< HW / board version (last 8 bytes should be silicon ID, if any)*/ - uint16_t vendor_id; /*< ID of the board vendor*/ - uint16_t product_id; /*< ID of the product*/ - uint8_t flight_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ - uint8_t middleware_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ - uint8_t os_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ -}) mavlink_autopilot_version_t; - -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60 -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN 60 -#define MAVLINK_MSG_ID_148_LEN 60 -#define MAVLINK_MSG_ID_148_MIN_LEN 60 - -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178 -#define MAVLINK_MSG_ID_148_CRC 178 - -#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN 8 -#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN 8 -#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \ - 148, \ - "AUTOPILOT_VERSION", \ - 11, \ - { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \ - { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ - { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \ - { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \ - { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \ - { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \ - { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ - { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ - { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \ - { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \ - { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \ - "AUTOPILOT_VERSION", \ - 11, \ - { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \ - { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ - { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \ - { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \ - { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \ - { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \ - { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ - { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ - { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \ - { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \ - { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \ - } \ -} -#endif - -/** - * @brief Pack a autopilot_version 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 capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#else - mavlink_autopilot_version_t packet; - packet.capabilities = capabilities; - packet.uid = uid; - packet.flight_sw_version = flight_sw_version; - packet.middleware_sw_version = middleware_sw_version; - packet.os_sw_version = os_sw_version; - packet.board_version = board_version; - packet.vendor_id = vendor_id; - packet.product_id = product_id; - mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -} - -/** - * @brief Pack a autopilot_version message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t capabilities,uint32_t flight_sw_version,uint32_t middleware_sw_version,uint32_t os_sw_version,uint32_t board_version,const uint8_t *flight_custom_version,const uint8_t *middleware_custom_version,const uint8_t *os_custom_version,uint16_t vendor_id,uint16_t product_id,uint64_t uid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#else - mavlink_autopilot_version_t packet; - packet.capabilities = capabilities; - packet.uid = uid; - packet.flight_sw_version = flight_sw_version; - packet.middleware_sw_version = middleware_sw_version; - packet.os_sw_version = os_sw_version; - packet.board_version = board_version; - packet.vendor_id = vendor_id; - packet.product_id = product_id; - mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -} - -/** - * @brief Encode a autopilot_version struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param autopilot_version C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_autopilot_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version) -{ - return mavlink_msg_autopilot_version_pack(system_id, component_id, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid); -} - -/** - * @brief Encode a autopilot_version struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param autopilot_version C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version) -{ - return mavlink_msg_autopilot_version_pack_chan(system_id, component_id, chan, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid); -} - -/** - * @brief Send a autopilot_version message - * @param chan MAVLink channel to send the message - * - * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#else - mavlink_autopilot_version_t packet; - packet.capabilities = capabilities; - packet.uid = uid; - packet.flight_sw_version = flight_sw_version; - packet.middleware_sw_version = middleware_sw_version; - packet.os_sw_version = os_sw_version; - packet.board_version = board_version; - packet.vendor_id = vendor_id; - packet.product_id = product_id; - mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#endif -} - -/** - * @brief Send a autopilot_version message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_autopilot_version_send_struct(mavlink_channel_t chan, const mavlink_autopilot_version_t* autopilot_version) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_autopilot_version_send(chan, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)autopilot_version, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#else - mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf; - packet->capabilities = capabilities; - packet->uid = uid; - packet->flight_sw_version = flight_sw_version; - packet->middleware_sw_version = middleware_sw_version; - packet->os_sw_version = os_sw_version; - packet->board_version = board_version; - packet->vendor_id = vendor_id; - packet->product_id = product_id; - mav_array_memcpy(packet->flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet->middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet->os_custom_version, os_custom_version, sizeof(uint8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE AUTOPILOT_VERSION UNPACKING - - -/** - * @brief Get field capabilities from autopilot_version message - * - * @return bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - */ -static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field flight_sw_version from autopilot_version message - * - * @return Firmware version number - */ -static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 16); -} - -/** - * @brief Get field middleware_sw_version from autopilot_version message - * - * @return Middleware version number - */ -static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field os_sw_version from autopilot_version message - * - * @return Operating system version number - */ -static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 24); -} - -/** - * @brief Get field board_version from autopilot_version message - * - * @return HW / board version (last 8 bytes should be silicon ID, if any) - */ -static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 28); -} - -/** - * @brief Get field flight_custom_version from autopilot_version message - * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - */ -static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t* msg, uint8_t *flight_custom_version) -{ - return _MAV_RETURN_uint8_t_array(msg, flight_custom_version, 8, 36); -} - -/** - * @brief Get field middleware_custom_version from autopilot_version message - * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - */ -static inline uint16_t mavlink_msg_autopilot_version_get_middleware_custom_version(const mavlink_message_t* msg, uint8_t *middleware_custom_version) -{ - return _MAV_RETURN_uint8_t_array(msg, middleware_custom_version, 8, 44); -} - -/** - * @brief Get field os_custom_version from autopilot_version message - * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - */ -static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t* msg, uint8_t *os_custom_version) -{ - return _MAV_RETURN_uint8_t_array(msg, os_custom_version, 8, 52); -} - -/** - * @brief Get field vendor_id from autopilot_version message - * - * @return ID of the board vendor - */ -static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field product_id from autopilot_version message - * - * @return ID of the product - */ -static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 34); -} - -/** - * @brief Get field uid from autopilot_version message - * - * @return UID if provided by hardware - */ -static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Decode a autopilot_version message into a struct - * - * @param msg The message to decode - * @param autopilot_version C-struct to decode the message contents into - */ -static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t* msg, mavlink_autopilot_version_t* autopilot_version) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - autopilot_version->capabilities = mavlink_msg_autopilot_version_get_capabilities(msg); - autopilot_version->uid = mavlink_msg_autopilot_version_get_uid(msg); - autopilot_version->flight_sw_version = mavlink_msg_autopilot_version_get_flight_sw_version(msg); - autopilot_version->middleware_sw_version = mavlink_msg_autopilot_version_get_middleware_sw_version(msg); - autopilot_version->os_sw_version = mavlink_msg_autopilot_version_get_os_sw_version(msg); - autopilot_version->board_version = mavlink_msg_autopilot_version_get_board_version(msg); - autopilot_version->vendor_id = mavlink_msg_autopilot_version_get_vendor_id(msg); - autopilot_version->product_id = mavlink_msg_autopilot_version_get_product_id(msg); - mavlink_msg_autopilot_version_get_flight_custom_version(msg, autopilot_version->flight_custom_version); - mavlink_msg_autopilot_version_get_middleware_custom_version(msg, autopilot_version->middleware_custom_version); - mavlink_msg_autopilot_version_get_os_custom_version(msg, autopilot_version->os_custom_version); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN? msg->len : MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN; - memset(autopilot_version, 0, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); - memcpy(autopilot_version, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_battery_status.h b/include/mavlink/v1.0/common/mavlink_msg_battery_status.h deleted file mode 100644 index d69a246..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_battery_status.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE BATTERY_STATUS PACKING - -#define MAVLINK_MSG_ID_BATTERY_STATUS 147 - -MAVPACKED( -typedef struct __mavlink_battery_status_t { - int32_t current_consumed; /*< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate*/ - int32_t energy_consumed; /*< Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate*/ - int16_t temperature; /*< Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.*/ - uint16_t voltages[10]; /*< Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.*/ - int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/ - uint8_t id; /*< Battery ID*/ - uint8_t battery_function; /*< Function of the battery*/ - uint8_t type; /*< Type (chemistry) of the battery*/ - int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery*/ -}) mavlink_battery_status_t; - -#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36 -#define MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN 36 -#define MAVLINK_MSG_ID_147_LEN 36 -#define MAVLINK_MSG_ID_147_MIN_LEN 36 - -#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154 -#define MAVLINK_MSG_ID_147_CRC 154 - -#define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ - 147, \ - "BATTERY_STATUS", \ - 9, \ - { { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ - { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \ - { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ - { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ - "BATTERY_STATUS", \ - 9, \ - { { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ - { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \ - { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ - { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \ - } \ -} -#endif - -/** - * @brief Pack a battery_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 id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.temperature = temperature; - packet.current_battery = current_battery; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.battery_remaining = battery_remaining; - mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); - 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, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -} - -/** - * @brief Pack a battery_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t id,uint8_t battery_function,uint8_t type,int16_t temperature,const uint16_t *voltages,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.temperature = temperature; - packet.current_battery = current_battery; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.battery_remaining = battery_remaining; - mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); - 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, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -} - -/** - * @brief Encode a battery_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param battery_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) -{ - return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); -} - -/** - * @brief Encode a battery_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param battery_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) -{ - return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); -} - -/** - * @brief Send a battery_status message - * @param chan MAVLink channel to send the message - * - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.temperature = temperature; - packet.current_battery = current_battery; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.battery_remaining = battery_remaining; - mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#endif -} - -/** - * @brief Send a battery_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_battery_status_send_struct(mavlink_channel_t chan, const mavlink_battery_status_t* battery_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_battery_status_send(chan, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)battery_status, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - mavlink_battery_status_t *packet = (mavlink_battery_status_t *)msgbuf; - packet->current_consumed = current_consumed; - packet->energy_consumed = energy_consumed; - packet->temperature = temperature; - packet->current_battery = current_battery; - packet->id = id; - packet->battery_function = battery_function; - packet->type = type; - packet->battery_remaining = battery_remaining; - mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE BATTERY_STATUS UNPACKING - - -/** - * @brief Get field id from battery_status message - * - * @return Battery ID - */ -static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field battery_function from battery_status message - * - * @return Function of the battery - */ -static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field type from battery_status message - * - * @return Type (chemistry) of the battery - */ -static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field temperature from battery_status message - * - * @return Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - */ -static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field voltages from battery_status message - * - * @return Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - */ -static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_message_t* msg, uint16_t *voltages) -{ - return _MAV_RETURN_uint16_t_array(msg, voltages, 10, 10); -} - -/** - * @brief Get field current_battery from battery_status message - * - * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - */ -static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 30); -} - -/** - * @brief Get field current_consumed from battery_status message - * - * @return Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - */ -static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field energy_consumed from battery_status message - * - * @return Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - */ -static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field battery_remaining from battery_status message - * - * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - */ -static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 35); -} - -/** - * @brief Decode a battery_status message into a struct - * - * @param msg The message to decode - * @param battery_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* msg, mavlink_battery_status_t* battery_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - battery_status->current_consumed = mavlink_msg_battery_status_get_current_consumed(msg); - battery_status->energy_consumed = mavlink_msg_battery_status_get_energy_consumed(msg); - battery_status->temperature = mavlink_msg_battery_status_get_temperature(msg); - mavlink_msg_battery_status_get_voltages(msg, battery_status->voltages); - battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg); - battery_status->id = mavlink_msg_battery_status_get_id(msg); - battery_status->battery_function = mavlink_msg_battery_status_get_battery_function(msg); - battery_status->type = mavlink_msg_battery_status_get_type(msg); - battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_BATTERY_STATUS_LEN? msg->len : MAVLINK_MSG_ID_BATTERY_STATUS_LEN; - memset(battery_status, 0, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); - memcpy(battery_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_camera_trigger.h b/include/mavlink/v1.0/common/mavlink_msg_camera_trigger.h deleted file mode 100644 index 71bb1c1..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_camera_trigger.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE CAMERA_TRIGGER PACKING - -#define MAVLINK_MSG_ID_CAMERA_TRIGGER 112 - -MAVPACKED( -typedef struct __mavlink_camera_trigger_t { - uint64_t time_usec; /*< Timestamp for the image frame in microseconds*/ - uint32_t seq; /*< Image frame sequence*/ -}) mavlink_camera_trigger_t; - -#define MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN 12 -#define MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN 12 -#define MAVLINK_MSG_ID_112_LEN 12 -#define MAVLINK_MSG_ID_112_MIN_LEN 12 - -#define MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC 174 -#define MAVLINK_MSG_ID_112_CRC 174 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER { \ - 112, \ - "CAMERA_TRIGGER", \ - 2, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_trigger_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_trigger_t, seq) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER { \ - "CAMERA_TRIGGER", \ - 2, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_trigger_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_trigger_t, seq) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_trigger 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 for the image frame in microseconds - * @param seq Image frame sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_trigger_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#else - mavlink_camera_trigger_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -} - -/** - * @brief Pack a camera_trigger message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp for the image frame in microseconds - * @param seq Image frame sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_trigger_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#else - mavlink_camera_trigger_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -} - -/** - * @brief Encode a camera_trigger struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_trigger C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_trigger_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger) -{ - return mavlink_msg_camera_trigger_pack(system_id, component_id, msg, camera_trigger->time_usec, camera_trigger->seq); -} - -/** - * @brief Encode a camera_trigger struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_trigger C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_trigger_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger) -{ - return mavlink_msg_camera_trigger_pack_chan(system_id, component_id, chan, msg, camera_trigger->time_usec, camera_trigger->seq); -} - -/** - * @brief Send a camera_trigger message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp for the image frame in microseconds - * @param seq Image frame sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_trigger_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#else - mavlink_camera_trigger_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#endif -} - -/** - * @brief Send a camera_trigger message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_trigger_send_struct(mavlink_channel_t chan, const mavlink_camera_trigger_t* camera_trigger) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_trigger_send(chan, camera_trigger->time_usec, camera_trigger->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)camera_trigger, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_trigger_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#else - mavlink_camera_trigger_t *packet = (mavlink_camera_trigger_t *)msgbuf; - packet->time_usec = time_usec; - packet->seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_TRIGGER UNPACKING - - -/** - * @brief Get field time_usec from camera_trigger message - * - * @return Timestamp for the image frame in microseconds - */ -static inline uint64_t mavlink_msg_camera_trigger_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field seq from camera_trigger message - * - * @return Image frame sequence - */ -static inline uint32_t mavlink_msg_camera_trigger_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Decode a camera_trigger message into a struct - * - * @param msg The message to decode - * @param camera_trigger C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_trigger_decode(const mavlink_message_t* msg, mavlink_camera_trigger_t* camera_trigger) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_trigger->time_usec = mavlink_msg_camera_trigger_get_time_usec(msg); - camera_trigger->seq = mavlink_msg_camera_trigger_get_seq(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN; - memset(camera_trigger, 0, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); - memcpy(camera_trigger, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h b/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h deleted file mode 100644 index b6e76f7..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE CHANGE_OPERATOR_CONTROL PACKING - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 - -MAVPACKED( -typedef struct __mavlink_change_operator_control_t { - uint8_t target_system; /*< System the GCS requests control for*/ - uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ - uint8_t version; /*< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/ - char passkey[25]; /*< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"*/ -}) mavlink_change_operator_control_t; - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN 28 -#define MAVLINK_MSG_ID_5_LEN 28 -#define MAVLINK_MSG_ID_5_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ - 5, \ - "CHANGE_OPERATOR_CONTROL", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ - { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ - { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ - "CHANGE_OPERATOR_CONTROL", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ - { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ - { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ - } \ -} -#endif - -/** - * @brief Pack a change_operator_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -} - -/** - * @brief Pack a change_operator_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -} - -/** - * @brief Encode a change_operator_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param change_operator_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) -{ - return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); -} - -/** - * @brief Encode a change_operator_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param change_operator_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) -{ - return mavlink_msg_change_operator_control_pack_chan(system_id, component_id, chan, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); -} - -/** - * @brief Send a change_operator_control message - * @param chan MAVLink channel to send the message - * - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#endif -} - -/** - * @brief Send a change_operator_control message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_change_operator_control_send_struct(mavlink_channel_t chan, const mavlink_change_operator_control_t* change_operator_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_change_operator_control_send(chan, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)change_operator_control, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_change_operator_control_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#else - mavlink_change_operator_control_t *packet = (mavlink_change_operator_control_t *)msgbuf; - 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING - - -/** - * @brief Get field target_system from change_operator_control message - * - * @return System the GCS requests control for - */ -static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field control_request from change_operator_control message - * - * @return 0: request control of this MAV, 1: Release control of this MAV - */ -static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field version from change_operator_control message - * - * @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - */ -static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field passkey from change_operator_control message - * - * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - */ -static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey) -{ - return _MAV_RETURN_char_array(msg, passkey, 25, 3); -} - -/** - * @brief Decode a change_operator_control message into a struct - * - * @param msg The message to decode - * @param change_operator_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg); - change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN; - memset(change_operator_control, 0, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); - memcpy(change_operator_control, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h b/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h deleted file mode 100644 index 16bcec8..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 - -MAVPACKED( -typedef struct __mavlink_change_operator_control_ack_t { - uint8_t gcs_system_id; /*< ID of the GCS this message */ - uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ - uint8_t ack; /*< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control*/ -}) mavlink_change_operator_control_ack_t; - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN 3 -#define MAVLINK_MSG_ID_6_LEN 3 -#define MAVLINK_MSG_ID_6_MIN_LEN 3 - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104 -#define MAVLINK_MSG_ID_6_CRC 104 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ - 6, \ - "CHANGE_OPERATOR_CONTROL_ACK", \ - 3, \ - { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ - { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ - "CHANGE_OPERATOR_CONTROL_ACK", \ - 3, \ - { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ - { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ - } \ -} -#endif - -/** - * @brief Pack a change_operator_control_ack 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 gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -} - -/** - * @brief Pack a change_operator_control_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t gcs_system_id,uint8_t control_request,uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -} - -/** - * @brief Encode a change_operator_control_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param change_operator_control_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ - return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); -} - -/** - * @brief Encode a change_operator_control_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param change_operator_control_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ - return mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, chan, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); -} - -/** - * @brief Send a change_operator_control_ack message - * @param chan MAVLink channel to send the message - * - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#endif -} - -/** - * @brief Send a change_operator_control_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_change_operator_control_ack_send_struct(mavlink_channel_t chan, const mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_change_operator_control_ack_send(chan, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)change_operator_control_ack, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_change_operator_control_ack_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#else - mavlink_change_operator_control_ack_t *packet = (mavlink_change_operator_control_ack_t *)msgbuf; - 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING - - -/** - * @brief Get field gcs_system_id from change_operator_control_ack message - * - * @return ID of the GCS this message - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field control_request from change_operator_control_ack message - * - * @return 0: request control of this MAV, 1: Release control of this MAV - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field ack from change_operator_control_ack message - * - * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a change_operator_control_ack message into a struct - * - * @param msg The message to decode - * @param change_operator_control_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN? msg->len : MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN; - memset(change_operator_control_ack, 0, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); - memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_collision.h b/include/mavlink/v1.0/common/mavlink_msg_collision.h deleted file mode 100644 index b888c20..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_collision.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE COLLISION PACKING - -#define MAVLINK_MSG_ID_COLLISION 247 - -MAVPACKED( -typedef struct __mavlink_collision_t { - uint32_t id; /*< Unique identifier, domain based on src field*/ - float time_to_minimum_delta; /*< Estimated time until collision occurs (seconds)*/ - float altitude_minimum_delta; /*< Closest vertical distance in meters between vehicle and object*/ - float horizontal_minimum_delta; /*< Closest horizontal distance in meteres between vehicle and object*/ - uint8_t src; /*< Collision data source*/ - uint8_t action; /*< Action that is being taken to avoid this collision*/ - uint8_t threat_level; /*< How concerned the aircraft is about this collision*/ -}) mavlink_collision_t; - -#define MAVLINK_MSG_ID_COLLISION_LEN 19 -#define MAVLINK_MSG_ID_COLLISION_MIN_LEN 19 -#define MAVLINK_MSG_ID_247_LEN 19 -#define MAVLINK_MSG_ID_247_MIN_LEN 19 - -#define MAVLINK_MSG_ID_COLLISION_CRC 81 -#define MAVLINK_MSG_ID_247_CRC 81 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COLLISION { \ - 247, \ - "COLLISION", \ - 7, \ - { { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \ - { "time_to_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_collision_t, time_to_minimum_delta) }, \ - { "altitude_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_collision_t, altitude_minimum_delta) }, \ - { "horizontal_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_collision_t, horizontal_minimum_delta) }, \ - { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \ - { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \ - { "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COLLISION { \ - "COLLISION", \ - 7, \ - { { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \ - { "time_to_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_collision_t, time_to_minimum_delta) }, \ - { "altitude_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_collision_t, altitude_minimum_delta) }, \ - { "horizontal_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_collision_t, horizontal_minimum_delta) }, \ - { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \ - { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \ - { "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \ - } \ -} -#endif - -/** - * @brief Pack a collision 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 src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta Estimated time until collision occurs (seconds) - * @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object - * @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_collision_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t src, uint32_t id, uint8_t action, uint8_t threat_level, float time_to_minimum_delta, float altitude_minimum_delta, float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COLLISION_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COLLISION_LEN); -#else - mavlink_collision_t packet; - packet.id = id; - packet.time_to_minimum_delta = time_to_minimum_delta; - packet.altitude_minimum_delta = altitude_minimum_delta; - packet.horizontal_minimum_delta = horizontal_minimum_delta; - packet.src = src; - packet.action = action; - packet.threat_level = threat_level; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COLLISION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COLLISION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -} - -/** - * @brief Pack a collision message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta Estimated time until collision occurs (seconds) - * @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object - * @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_collision_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t src,uint32_t id,uint8_t action,uint8_t threat_level,float time_to_minimum_delta,float altitude_minimum_delta,float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COLLISION_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COLLISION_LEN); -#else - mavlink_collision_t packet; - packet.id = id; - packet.time_to_minimum_delta = time_to_minimum_delta; - packet.altitude_minimum_delta = altitude_minimum_delta; - packet.horizontal_minimum_delta = horizontal_minimum_delta; - packet.src = src; - packet.action = action; - packet.threat_level = threat_level; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COLLISION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COLLISION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -} - -/** - * @brief Encode a collision struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param collision C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_collision_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_collision_t* collision) -{ - return mavlink_msg_collision_pack(system_id, component_id, msg, collision->src, collision->id, collision->action, collision->threat_level, collision->time_to_minimum_delta, collision->altitude_minimum_delta, collision->horizontal_minimum_delta); -} - -/** - * @brief Encode a collision struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param collision C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_collision_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_collision_t* collision) -{ - return mavlink_msg_collision_pack_chan(system_id, component_id, chan, msg, collision->src, collision->id, collision->action, collision->threat_level, collision->time_to_minimum_delta, collision->altitude_minimum_delta, collision->horizontal_minimum_delta); -} - -/** - * @brief Send a collision message - * @param chan MAVLink channel to send the message - * - * @param src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta Estimated time until collision occurs (seconds) - * @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object - * @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_collision_send(mavlink_channel_t chan, uint8_t src, uint32_t id, uint8_t action, uint8_t threat_level, float time_to_minimum_delta, float altitude_minimum_delta, float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COLLISION_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, buf, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#else - mavlink_collision_t packet; - packet.id = id; - packet.time_to_minimum_delta = time_to_minimum_delta; - packet.altitude_minimum_delta = altitude_minimum_delta; - packet.horizontal_minimum_delta = horizontal_minimum_delta; - packet.src = src; - packet.action = action; - packet.threat_level = threat_level; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, (const char *)&packet, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#endif -} - -/** - * @brief Send a collision message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_collision_send_struct(mavlink_channel_t chan, const mavlink_collision_t* collision) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_collision_send(chan, collision->src, collision->id, collision->action, collision->threat_level, collision->time_to_minimum_delta, collision->altitude_minimum_delta, collision->horizontal_minimum_delta); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, (const char *)collision, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COLLISION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_collision_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t src, uint32_t id, uint8_t action, uint8_t threat_level, float time_to_minimum_delta, float altitude_minimum_delta, float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, buf, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#else - mavlink_collision_t *packet = (mavlink_collision_t *)msgbuf; - packet->id = id; - packet->time_to_minimum_delta = time_to_minimum_delta; - packet->altitude_minimum_delta = altitude_minimum_delta; - packet->horizontal_minimum_delta = horizontal_minimum_delta; - packet->src = src; - packet->action = action; - packet->threat_level = threat_level; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, (const char *)packet, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COLLISION UNPACKING - - -/** - * @brief Get field src from collision message - * - * @return Collision data source - */ -static inline uint8_t mavlink_msg_collision_get_src(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field id from collision message - * - * @return Unique identifier, domain based on src field - */ -static inline uint32_t mavlink_msg_collision_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field action from collision message - * - * @return Action that is being taken to avoid this collision - */ -static inline uint8_t mavlink_msg_collision_get_action(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field threat_level from collision message - * - * @return How concerned the aircraft is about this collision - */ -static inline uint8_t mavlink_msg_collision_get_threat_level(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field time_to_minimum_delta from collision message - * - * @return Estimated time until collision occurs (seconds) - */ -static inline float mavlink_msg_collision_get_time_to_minimum_delta(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field altitude_minimum_delta from collision message - * - * @return Closest vertical distance in meters between vehicle and object - */ -static inline float mavlink_msg_collision_get_altitude_minimum_delta(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field horizontal_minimum_delta from collision message - * - * @return Closest horizontal distance in meteres between vehicle and object - */ -static inline float mavlink_msg_collision_get_horizontal_minimum_delta(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a collision message into a struct - * - * @param msg The message to decode - * @param collision C-struct to decode the message contents into - */ -static inline void mavlink_msg_collision_decode(const mavlink_message_t* msg, mavlink_collision_t* collision) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - collision->id = mavlink_msg_collision_get_id(msg); - collision->time_to_minimum_delta = mavlink_msg_collision_get_time_to_minimum_delta(msg); - collision->altitude_minimum_delta = mavlink_msg_collision_get_altitude_minimum_delta(msg); - collision->horizontal_minimum_delta = mavlink_msg_collision_get_horizontal_minimum_delta(msg); - collision->src = mavlink_msg_collision_get_src(msg); - collision->action = mavlink_msg_collision_get_action(msg); - collision->threat_level = mavlink_msg_collision_get_threat_level(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COLLISION_LEN? msg->len : MAVLINK_MSG_ID_COLLISION_LEN; - memset(collision, 0, MAVLINK_MSG_ID_COLLISION_LEN); - memcpy(collision, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_command_ack.h b/include/mavlink/v1.0/common/mavlink_msg_command_ack.h deleted file mode 100644 index 7ace685..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_command_ack.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE COMMAND_ACK PACKING - -#define MAVLINK_MSG_ID_COMMAND_ACK 77 - -MAVPACKED( -typedef struct __mavlink_command_ack_t { - uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/ - uint8_t result; /*< See MAV_RESULT enum*/ -}) mavlink_command_ack_t; - -#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 -#define MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN 3 -#define MAVLINK_MSG_ID_77_LEN 3 -#define MAVLINK_MSG_ID_77_MIN_LEN 3 - -#define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143 -#define MAVLINK_MSG_ID_77_CRC 143 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ - 77, \ - "COMMAND_ACK", \ - 2, \ - { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ - { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ - "COMMAND_ACK", \ - 2, \ - { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ - { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \ - } \ -} -#endif - -/** - * @brief Pack a command_ack 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 command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t command, uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -} - -/** - * @brief Pack a command_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t command,uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -} - -/** - * @brief Encode a command_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) -{ - return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result); -} - -/** - * @brief Encode a command_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) -{ - return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result); -} - -/** - * @brief Send a command_ack message - * @param chan MAVLink channel to send the message - * - * @param command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#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, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#endif -} - -/** - * @brief Send a command_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_command_ack_send_struct(mavlink_channel_t chan, const mavlink_command_ack_t* command_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_command_ack_send(chan, command_ack->command, command_ack->result); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)command_ack, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, result); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#else - mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf; - packet->command = command; - packet->result = result; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_ACK UNPACKING - - -/** - * @brief Get field command from command_ack message - * - * @return Command ID, as defined by MAV_CMD enum. - */ -static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field result from command_ack message - * - * @return See MAV_RESULT enum - */ -static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a command_ack message into a struct - * - * @param msg The message to decode - * @param command_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - command_ack->command = mavlink_msg_command_ack_get_command(msg); - command_ack->result = mavlink_msg_command_ack_get_result(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_ACK_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_ACK_LEN; - memset(command_ack, 0, MAVLINK_MSG_ID_COMMAND_ACK_LEN); - memcpy(command_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_command_int.h b/include/mavlink/v1.0/common/mavlink_msg_command_int.h deleted file mode 100644 index 7636346..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_command_int.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE COMMAND_INT PACKING - -#define MAVLINK_MSG_ID_COMMAND_INT 75 - -MAVPACKED( -typedef struct __mavlink_command_int_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ - int32_t y; /*< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7*/ - float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ - uint16_t command; /*< The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h*/ - uint8_t current; /*< false:0, true:1*/ - uint8_t autocontinue; /*< autocontinue to next wp*/ -}) mavlink_command_int_t; - -#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35 -#define MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN 35 -#define MAVLINK_MSG_ID_75_LEN 35 -#define MAVLINK_MSG_ID_75_MIN_LEN 35 - -#define MAVLINK_MSG_ID_COMMAND_INT_CRC 158 -#define MAVLINK_MSG_ID_75_CRC 158 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \ - 75, \ - "COMMAND_INT", \ - 13, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \ - "COMMAND_INT", \ - 13, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ - } \ -} -#endif - -/** - * @brief Pack a command_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#else - mavlink_command_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -} - -/** - * @brief Pack a command_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#else - mavlink_command_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -} - -/** - * @brief Encode a command_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_int_t* command_int) -{ - return mavlink_msg_command_int_pack(system_id, component_id, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); -} - -/** - * @brief Encode a command_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_int_t* command_int) -{ - return mavlink_msg_command_int_pack_chan(system_id, component_id, chan, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); -} - -/** - * @brief Send a command_int message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_command_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#else - mavlink_command_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#endif -} - -/** - * @brief Send a command_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_command_int_send_struct(mavlink_channel_t chan, const mavlink_command_int_t* command_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_command_int_send(chan, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)command_int, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#else - mavlink_command_int_t *packet = (mavlink_command_int_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->x = x; - packet->y = y; - packet->z = z; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - packet->current = current; - packet->autocontinue = autocontinue; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_INT UNPACKING - - -/** - * @brief Get field target_system from command_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_command_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field target_component from command_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field frame from command_int message - * - * @return The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - */ -static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field command from command_int message - * - * @return The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - */ -static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field current from command_int message - * - * @return false:0, true:1 - */ -static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field autocontinue from command_int message - * - * @return autocontinue to next wp - */ -static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field param1 from command_int message - * - * @return PARAM1, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from command_int message - * - * @return PARAM2, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from command_int message - * - * @return PARAM3, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from command_int message - * - * @return PARAM4, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field x from command_int message - * - * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - */ -static inline int32_t mavlink_msg_command_int_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field y from command_int message - * - * @return PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - */ -static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field z from command_int message - * - * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - */ -static inline float mavlink_msg_command_int_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a command_int message into a struct - * - * @param msg The message to decode - * @param command_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_int_decode(const mavlink_message_t* msg, mavlink_command_int_t* command_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - command_int->param1 = mavlink_msg_command_int_get_param1(msg); - command_int->param2 = mavlink_msg_command_int_get_param2(msg); - command_int->param3 = mavlink_msg_command_int_get_param3(msg); - command_int->param4 = mavlink_msg_command_int_get_param4(msg); - command_int->x = mavlink_msg_command_int_get_x(msg); - command_int->y = mavlink_msg_command_int_get_y(msg); - command_int->z = mavlink_msg_command_int_get_z(msg); - command_int->command = mavlink_msg_command_int_get_command(msg); - command_int->target_system = mavlink_msg_command_int_get_target_system(msg); - command_int->target_component = mavlink_msg_command_int_get_target_component(msg); - command_int->frame = mavlink_msg_command_int_get_frame(msg); - command_int->current = mavlink_msg_command_int_get_current(msg); - command_int->autocontinue = mavlink_msg_command_int_get_autocontinue(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_INT_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_INT_LEN; - memset(command_int, 0, MAVLINK_MSG_ID_COMMAND_INT_LEN); - memcpy(command_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_command_long.h b/include/mavlink/v1.0/common/mavlink_msg_command_long.h deleted file mode 100644 index f7c62cb..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_command_long.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE COMMAND_LONG PACKING - -#define MAVLINK_MSG_ID_COMMAND_LONG 76 - -MAVPACKED( -typedef struct __mavlink_command_long_t { - float param1; /*< Parameter 1, as defined by MAV_CMD enum.*/ - float param2; /*< Parameter 2, as defined by MAV_CMD enum.*/ - float param3; /*< Parameter 3, as defined by MAV_CMD enum.*/ - float param4; /*< Parameter 4, as defined by MAV_CMD enum.*/ - float param5; /*< Parameter 5, as defined by MAV_CMD enum.*/ - float param6; /*< Parameter 6, as defined by MAV_CMD enum.*/ - float param7; /*< Parameter 7, as defined by MAV_CMD enum.*/ - uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/ - uint8_t target_system; /*< System which should execute the command*/ - uint8_t target_component; /*< Component which should execute the command, 0 for all components*/ - uint8_t confirmation; /*< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)*/ -}) mavlink_command_long_t; - -#define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 -#define MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN 33 -#define MAVLINK_MSG_ID_76_LEN 33 -#define MAVLINK_MSG_ID_76_MIN_LEN 33 - -#define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152 -#define MAVLINK_MSG_ID_76_CRC 152 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ - 76, \ - "COMMAND_LONG", \ - 11, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ - { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ - { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ - { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ - { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ - "COMMAND_LONG", \ - 11, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ - { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ - { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ - { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ - { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ - } \ -} -#endif - -/** - * @brief Pack a command_long message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - - 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, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -} - -/** - * @brief Pack a command_long message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - - 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, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -} - -/** - * @brief Encode a command_long struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_long C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_long_t* command_long) -{ - return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); -} - -/** - * @brief Encode a command_long struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_long C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_long_t* command_long) -{ - return mavlink_msg_command_long_pack_chan(system_id, component_id, chan, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); -} - -/** - * @brief Send a command_long message - * @param chan MAVLink channel to send the message - * - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _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, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#endif -} - -/** - * @brief Send a command_long message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_command_long_send_struct(mavlink_channel_t chan, const mavlink_command_long_t* command_long) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_command_long_send(chan, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)command_long, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_long_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _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, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - mavlink_command_long_t *packet = (mavlink_command_long_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->param5 = param5; - packet->param6 = param6; - packet->param7 = param7; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->confirmation = confirmation; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_LONG UNPACKING - - -/** - * @brief Get field target_system from command_long message - * - * @return System which should execute the command - */ -static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field target_component from command_long message - * - * @return Component which should execute the command, 0 for all components - */ -static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field command from command_long message - * - * @return Command ID, as defined by MAV_CMD enum. - */ -static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field confirmation from command_long message - * - * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - */ -static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field param1 from command_long message - * - * @return Parameter 1, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from command_long message - * - * @return Parameter 2, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from command_long message - * - * @return Parameter 3, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from command_long message - * - * @return Parameter 4, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field param5 from command_long message - * - * @return Parameter 5, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field param6 from command_long message - * - * @return Parameter 6, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field param7 from command_long message - * - * @return Parameter 7, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a command_long message into a struct - * - * @param msg The message to decode - * @param command_long C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, mavlink_command_long_t* command_long) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - command_long->param1 = mavlink_msg_command_long_get_param1(msg); - command_long->param2 = mavlink_msg_command_long_get_param2(msg); - command_long->param3 = mavlink_msg_command_long_get_param3(msg); - command_long->param4 = mavlink_msg_command_long_get_param4(msg); - command_long->param5 = mavlink_msg_command_long_get_param5(msg); - command_long->param6 = mavlink_msg_command_long_get_param6(msg); - command_long->param7 = mavlink_msg_command_long_get_param7(msg); - command_long->command = mavlink_msg_command_long_get_command(msg); - command_long->target_system = mavlink_msg_command_long_get_target_system(msg); - command_long->target_component = mavlink_msg_command_long_get_target_component(msg); - command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_LONG_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_LONG_LEN; - memset(command_long, 0, MAVLINK_MSG_ID_COMMAND_LONG_LEN); - memcpy(command_long, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_control_system_state.h b/include/mavlink/v1.0/common/mavlink_msg_control_system_state.h deleted file mode 100644 index 8914b6a..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_control_system_state.h +++ /dev/null @@ -1,607 +0,0 @@ -#pragma once -// MESSAGE CONTROL_SYSTEM_STATE PACKING - -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE 146 - -MAVPACKED( -typedef struct __mavlink_control_system_state_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float x_acc; /*< X acceleration in body frame*/ - float y_acc; /*< Y acceleration in body frame*/ - float z_acc; /*< Z acceleration in body frame*/ - float x_vel; /*< X velocity in body frame*/ - float y_vel; /*< Y velocity in body frame*/ - float z_vel; /*< Z velocity in body frame*/ - float x_pos; /*< X position in local frame*/ - float y_pos; /*< Y position in local frame*/ - float z_pos; /*< Z position in local frame*/ - float airspeed; /*< Airspeed, set to -1 if unknown*/ - float vel_variance[3]; /*< Variance of body velocity estimate*/ - float pos_variance[3]; /*< Variance in local position*/ - float q[4]; /*< The attitude, represented as Quaternion*/ - float roll_rate; /*< Angular rate in roll axis*/ - float pitch_rate; /*< Angular rate in pitch axis*/ - float yaw_rate; /*< Angular rate in yaw axis*/ -}) mavlink_control_system_state_t; - -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN 100 -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN 100 -#define MAVLINK_MSG_ID_146_LEN 100 -#define MAVLINK_MSG_ID_146_MIN_LEN 100 - -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC 103 -#define MAVLINK_MSG_ID_146_CRC 103 - -#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_VEL_VARIANCE_LEN 3 -#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_POS_VARIANCE_LEN 3 -#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \ - 146, \ - "CONTROL_SYSTEM_STATE", \ - 17, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \ - { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \ - { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \ - { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \ - { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \ - { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \ - { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \ - { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \ - { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \ - { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \ - { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \ - { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \ - { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \ - { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \ - { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \ - "CONTROL_SYSTEM_STATE", \ - 17, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \ - { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \ - { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \ - { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \ - { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \ - { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \ - { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \ - { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \ - { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \ - { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \ - { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \ - { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \ - { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \ - { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \ - { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \ - } \ -} -#endif - -/** - * @brief Pack a control_system_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 time_usec Timestamp (micros since boot or Unix epoch) - * @param x_acc X acceleration in body frame - * @param y_acc Y acceleration in body frame - * @param z_acc Z acceleration in body frame - * @param x_vel X velocity in body frame - * @param y_vel Y velocity in body frame - * @param z_vel Z velocity in body frame - * @param x_pos X position in local frame - * @param y_pos Y position in local frame - * @param z_pos Z position in local frame - * @param airspeed Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate Angular rate in roll axis - * @param pitch_rate Angular rate in pitch axis - * @param yaw_rate Angular rate in yaw axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#else - mavlink_control_system_state_t packet; - packet.time_usec = time_usec; - packet.x_acc = x_acc; - packet.y_acc = y_acc; - packet.z_acc = z_acc; - packet.x_vel = x_vel; - packet.y_vel = y_vel; - packet.z_vel = z_vel; - packet.x_pos = x_pos; - packet.y_pos = y_pos; - packet.z_pos = z_pos; - packet.airspeed = airspeed; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -} - -/** - * @brief Pack a control_system_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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param x_acc X acceleration in body frame - * @param y_acc Y acceleration in body frame - * @param z_acc Z acceleration in body frame - * @param x_vel X velocity in body frame - * @param y_vel Y velocity in body frame - * @param z_vel Z velocity in body frame - * @param x_pos X position in local frame - * @param y_pos Y position in local frame - * @param z_pos Z position in local frame - * @param airspeed Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate Angular rate in roll axis - * @param pitch_rate Angular rate in pitch axis - * @param yaw_rate Angular rate in yaw axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_control_system_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float x_acc,float y_acc,float z_acc,float x_vel,float y_vel,float z_vel,float x_pos,float y_pos,float z_pos,float airspeed,const float *vel_variance,const float *pos_variance,const float *q,float roll_rate,float pitch_rate,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#else - mavlink_control_system_state_t packet; - packet.time_usec = time_usec; - packet.x_acc = x_acc; - packet.y_acc = y_acc; - packet.z_acc = z_acc; - packet.x_vel = x_vel; - packet.y_vel = y_vel; - packet.z_vel = z_vel; - packet.x_pos = x_pos; - packet.y_pos = y_pos; - packet.z_pos = z_pos; - packet.airspeed = airspeed; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -} - -/** - * @brief Encode a control_system_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param control_system_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_control_system_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state) -{ - return mavlink_msg_control_system_state_pack(system_id, component_id, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); -} - -/** - * @brief Encode a control_system_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param control_system_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_control_system_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state) -{ - return mavlink_msg_control_system_state_pack_chan(system_id, component_id, chan, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); -} - -/** - * @brief Send a control_system_state message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param x_acc X acceleration in body frame - * @param y_acc Y acceleration in body frame - * @param z_acc Z acceleration in body frame - * @param x_vel X velocity in body frame - * @param y_vel Y velocity in body frame - * @param z_vel Z velocity in body frame - * @param x_pos X position in local frame - * @param y_pos Y position in local frame - * @param z_pos Z position in local frame - * @param airspeed Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate Angular rate in roll axis - * @param pitch_rate Angular rate in pitch axis - * @param yaw_rate Angular rate in yaw axis - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_control_system_state_send(mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#else - mavlink_control_system_state_t packet; - packet.time_usec = time_usec; - packet.x_acc = x_acc; - packet.y_acc = y_acc; - packet.z_acc = z_acc; - packet.x_vel = x_vel; - packet.y_vel = y_vel; - packet.z_vel = z_vel; - packet.x_pos = x_pos; - packet.y_pos = y_pos; - packet.z_pos = z_pos; - packet.airspeed = airspeed; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)&packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#endif -} - -/** - * @brief Send a control_system_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_control_system_state_send_struct(mavlink_channel_t chan, const mavlink_control_system_state_t* control_system_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_control_system_state_send(chan, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)control_system_state, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_control_system_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#else - mavlink_control_system_state_t *packet = (mavlink_control_system_state_t *)msgbuf; - packet->time_usec = time_usec; - packet->x_acc = x_acc; - packet->y_acc = y_acc; - packet->z_acc = z_acc; - packet->x_vel = x_vel; - packet->y_vel = y_vel; - packet->z_vel = z_vel; - packet->x_pos = x_pos; - packet->y_pos = y_pos; - packet->z_pos = z_pos; - packet->airspeed = airspeed; - packet->roll_rate = roll_rate; - packet->pitch_rate = pitch_rate; - packet->yaw_rate = yaw_rate; - mav_array_memcpy(packet->vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet->pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CONTROL_SYSTEM_STATE UNPACKING - - -/** - * @brief Get field time_usec from control_system_state message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_control_system_state_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x_acc from control_system_state message - * - * @return X acceleration in body frame - */ -static inline float mavlink_msg_control_system_state_get_x_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y_acc from control_system_state message - * - * @return Y acceleration in body frame - */ -static inline float mavlink_msg_control_system_state_get_y_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z_acc from control_system_state message - * - * @return Z acceleration in body frame - */ -static inline float mavlink_msg_control_system_state_get_z_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field x_vel from control_system_state message - * - * @return X velocity in body frame - */ -static inline float mavlink_msg_control_system_state_get_x_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field y_vel from control_system_state message - * - * @return Y velocity in body frame - */ -static inline float mavlink_msg_control_system_state_get_y_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field z_vel from control_system_state message - * - * @return Z velocity in body frame - */ -static inline float mavlink_msg_control_system_state_get_z_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field x_pos from control_system_state message - * - * @return X position in local frame - */ -static inline float mavlink_msg_control_system_state_get_x_pos(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field y_pos from control_system_state message - * - * @return Y position in local frame - */ -static inline float mavlink_msg_control_system_state_get_y_pos(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field z_pos from control_system_state message - * - * @return Z position in local frame - */ -static inline float mavlink_msg_control_system_state_get_z_pos(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field airspeed from control_system_state message - * - * @return Airspeed, set to -1 if unknown - */ -static inline float mavlink_msg_control_system_state_get_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field vel_variance from control_system_state message - * - * @return Variance of body velocity estimate - */ -static inline uint16_t mavlink_msg_control_system_state_get_vel_variance(const mavlink_message_t* msg, float *vel_variance) -{ - return _MAV_RETURN_float_array(msg, vel_variance, 3, 48); -} - -/** - * @brief Get field pos_variance from control_system_state message - * - * @return Variance in local position - */ -static inline uint16_t mavlink_msg_control_system_state_get_pos_variance(const mavlink_message_t* msg, float *pos_variance) -{ - return _MAV_RETURN_float_array(msg, pos_variance, 3, 60); -} - -/** - * @brief Get field q from control_system_state message - * - * @return The attitude, represented as Quaternion - */ -static inline uint16_t mavlink_msg_control_system_state_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 72); -} - -/** - * @brief Get field roll_rate from control_system_state message - * - * @return Angular rate in roll axis - */ -static inline float mavlink_msg_control_system_state_get_roll_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 88); -} - -/** - * @brief Get field pitch_rate from control_system_state message - * - * @return Angular rate in pitch axis - */ -static inline float mavlink_msg_control_system_state_get_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 92); -} - -/** - * @brief Get field yaw_rate from control_system_state message - * - * @return Angular rate in yaw axis - */ -static inline float mavlink_msg_control_system_state_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 96); -} - -/** - * @brief Decode a control_system_state message into a struct - * - * @param msg The message to decode - * @param control_system_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_control_system_state_decode(const mavlink_message_t* msg, mavlink_control_system_state_t* control_system_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - control_system_state->time_usec = mavlink_msg_control_system_state_get_time_usec(msg); - control_system_state->x_acc = mavlink_msg_control_system_state_get_x_acc(msg); - control_system_state->y_acc = mavlink_msg_control_system_state_get_y_acc(msg); - control_system_state->z_acc = mavlink_msg_control_system_state_get_z_acc(msg); - control_system_state->x_vel = mavlink_msg_control_system_state_get_x_vel(msg); - control_system_state->y_vel = mavlink_msg_control_system_state_get_y_vel(msg); - control_system_state->z_vel = mavlink_msg_control_system_state_get_z_vel(msg); - control_system_state->x_pos = mavlink_msg_control_system_state_get_x_pos(msg); - control_system_state->y_pos = mavlink_msg_control_system_state_get_y_pos(msg); - control_system_state->z_pos = mavlink_msg_control_system_state_get_z_pos(msg); - control_system_state->airspeed = mavlink_msg_control_system_state_get_airspeed(msg); - mavlink_msg_control_system_state_get_vel_variance(msg, control_system_state->vel_variance); - mavlink_msg_control_system_state_get_pos_variance(msg, control_system_state->pos_variance); - mavlink_msg_control_system_state_get_q(msg, control_system_state->q); - control_system_state->roll_rate = mavlink_msg_control_system_state_get_roll_rate(msg); - control_system_state->pitch_rate = mavlink_msg_control_system_state_get_pitch_rate(msg); - control_system_state->yaw_rate = mavlink_msg_control_system_state_get_yaw_rate(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN? msg->len : MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN; - memset(control_system_state, 0, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); - memcpy(control_system_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_data_stream.h b/include/mavlink/v1.0/common/mavlink_msg_data_stream.h deleted file mode 100644 index cceca20..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_data_stream.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE DATA_STREAM PACKING - -#define MAVLINK_MSG_ID_DATA_STREAM 67 - -MAVPACKED( -typedef struct __mavlink_data_stream_t { - uint16_t message_rate; /*< The message rate*/ - uint8_t stream_id; /*< The ID of the requested data stream*/ - uint8_t on_off; /*< 1 stream is enabled, 0 stream is stopped.*/ -}) mavlink_data_stream_t; - -#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4 -#define MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN 4 -#define MAVLINK_MSG_ID_67_LEN 4 -#define MAVLINK_MSG_ID_67_MIN_LEN 4 - -#define MAVLINK_MSG_ID_DATA_STREAM_CRC 21 -#define MAVLINK_MSG_ID_67_CRC 21 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ - 67, \ - "DATA_STREAM", \ - 3, \ - { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ - { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ - { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ - "DATA_STREAM", \ - 3, \ - { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ - { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ - { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ - } \ -} -#endif - -/** - * @brief Pack a data_stream 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 stream_id The ID of the requested data stream - * @param message_rate The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t stream_id, uint16_t message_rate, uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -} - -/** - * @brief Pack a data_stream message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param stream_id The ID of the requested data stream - * @param message_rate The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t stream_id,uint16_t message_rate,uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -} - -/** - * @brief Encode a data_stream struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) -{ - return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); -} - -/** - * @brief Encode a data_stream struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) -{ - return mavlink_msg_data_stream_pack_chan(system_id, component_id, chan, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); -} - -/** - * @brief Send a data_stream message - * @param chan MAVLink channel to send the message - * - * @param stream_id The ID of the requested data stream - * @param message_rate The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#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, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#endif -} - -/** - * @brief Send a data_stream message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_data_stream_send_struct(mavlink_channel_t chan, const mavlink_data_stream_t* data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_data_stream_send(chan, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)data_stream, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data_stream_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#else - mavlink_data_stream_t *packet = (mavlink_data_stream_t *)msgbuf; - 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, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DATA_STREAM UNPACKING - - -/** - * @brief Get field stream_id from data_stream message - * - * @return The ID of the requested data stream - */ -static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field message_rate from data_stream message - * - * @return The message rate - */ -static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field on_off from data_stream message - * - * @return 1 stream is enabled, 0 stream is stopped. - */ -static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Decode a data_stream message into a struct - * - * @param msg The message to decode - * @param data_stream C-struct to decode the message contents into - */ -static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, mavlink_data_stream_t* data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - data_stream->message_rate = mavlink_msg_data_stream_get_message_rate(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 - uint8_t len = msg->len < MAVLINK_MSG_ID_DATA_STREAM_LEN? msg->len : MAVLINK_MSG_ID_DATA_STREAM_LEN; - memset(data_stream, 0, MAVLINK_MSG_ID_DATA_STREAM_LEN); - memcpy(data_stream, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h b/include/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h deleted file mode 100644 index f607e39..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130 - -MAVPACKED( -typedef struct __mavlink_data_transmission_handshake_t { - uint32_t size; /*< total data size in bytes (set on ACK only)*/ - uint16_t width; /*< Width of a matrix or image*/ - uint16_t height; /*< Height of a matrix or image*/ - uint16_t packets; /*< number of packets beeing sent (set on ACK only)*/ - uint8_t type; /*< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)*/ - uint8_t payload; /*< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)*/ - uint8_t jpg_quality; /*< JPEG quality out of [1,100]*/ -}) mavlink_data_transmission_handshake_t; - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13 -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN 13 -#define MAVLINK_MSG_ID_130_LEN 13 -#define MAVLINK_MSG_ID_130_MIN_LEN 13 - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29 -#define MAVLINK_MSG_ID_130_CRC 29 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ - 130, \ - "DATA_TRANSMISSION_HANDSHAKE", \ - 7, \ - { { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ - { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ - { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ - { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ - { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ - "DATA_TRANSMISSION_HANDSHAKE", \ - 7, \ - { { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ - { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ - { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ - { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ - { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ - } \ -} -#endif - -/** - * @brief Pack a data_transmission_handshake message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - - 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, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -} - -/** - * @brief Pack a data_transmission_handshake message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint16_t packets,uint8_t payload,uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - - 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, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -} - -/** - * @brief Encode a data_transmission_handshake struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data_transmission_handshake C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ - return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); -} - -/** - * @brief Encode a data_transmission_handshake struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data_transmission_handshake C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ - return mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, chan, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); -} - -/** - * @brief Send a data_transmission_handshake message - * @param chan MAVLink channel to send the message - * - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#endif -} - -/** - * @brief Send a data_transmission_handshake message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_data_transmission_handshake_send_struct(mavlink_channel_t chan, const mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_data_transmission_handshake_send(chan, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)data_transmission_handshake, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data_transmission_handshake_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, size); - _mav_put_uint16_t(buf, 4, width); - _mav_put_uint16_t(buf, 6, height); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - mavlink_data_transmission_handshake_t *packet = (mavlink_data_transmission_handshake_t *)msgbuf; - packet->size = size; - packet->width = width; - packet->height = height; - packet->packets = packets; - packet->type = type; - packet->payload = payload; - packet->jpg_quality = jpg_quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING - - -/** - * @brief Get field type from data_transmission_handshake message - * - * @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field size from data_transmission_handshake message - * - * @return total data size in bytes (set on ACK only) - */ -static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field width from data_transmission_handshake message - * - * @return Width of a matrix or image - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field height from data_transmission_handshake message - * - * @return Height of a matrix or image - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field packets from data_transmission_handshake message - * - * @return number of packets beeing sent (set on ACK only) - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field payload from data_transmission_handshake message - * - * @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field jpg_quality from data_transmission_handshake message - * - * @return JPEG quality out of [1,100] - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Decode a data_transmission_handshake message into a struct - * - * @param msg The message to decode - * @param data_transmission_handshake C-struct to decode the message contents into - */ -static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg); - data_transmission_handshake->width = mavlink_msg_data_transmission_handshake_get_width(msg); - data_transmission_handshake->height = mavlink_msg_data_transmission_handshake_get_height(msg); - data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg); - data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN? msg->len : MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN; - memset(data_transmission_handshake, 0, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); - memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_debug.h b/include/mavlink/v1.0/common/mavlink_msg_debug.h deleted file mode 100644 index d762a89..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_debug.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE DEBUG PACKING - -#define MAVLINK_MSG_ID_DEBUG 254 - -MAVPACKED( -typedef struct __mavlink_debug_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float value; /*< DEBUG value*/ - uint8_t ind; /*< index of debug variable*/ -}) mavlink_debug_t; - -#define MAVLINK_MSG_ID_DEBUG_LEN 9 -#define MAVLINK_MSG_ID_DEBUG_MIN_LEN 9 -#define MAVLINK_MSG_ID_254_LEN 9 -#define MAVLINK_MSG_ID_254_MIN_LEN 9 - -#define MAVLINK_MSG_ID_DEBUG_CRC 46 -#define MAVLINK_MSG_ID_254_CRC 46 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DEBUG { \ - 254, \ - "DEBUG", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ - { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DEBUG { \ - "DEBUG", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ - { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ - } \ -} -#endif - -/** - * @brief Pack a debug 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_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t ind, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_DEBUG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -} - -/** - * @brief Pack a debug message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t ind,float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_DEBUG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -} - -/** - * @brief Encode a debug struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param debug C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug) -{ - return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value); -} - -/** - * @brief Encode a debug struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param debug C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_t* debug) -{ - return mavlink_msg_debug_pack_chan(system_id, component_id, chan, msg, debug->time_boot_ms, debug->ind, debug->value); -} - -/** - * @brief Send a debug message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#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, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#endif -} - -/** - * @brief Send a debug message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_debug_send_struct(mavlink_channel_t chan, const mavlink_debug_t* debug) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_debug_send(chan, debug->time_boot_ms, debug->ind, debug->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)debug, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DEBUG_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_debug_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#else - mavlink_debug_t *packet = (mavlink_debug_t *)msgbuf; - 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, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DEBUG UNPACKING - - -/** - * @brief Get field time_boot_ms from debug message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field ind from debug message - * - * @return index of debug variable - */ -static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field value from debug message - * - * @return DEBUG value - */ -static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Decode a debug message into a struct - * - * @param msg The message to decode - * @param debug C-struct to decode the message contents into - */ -static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - debug->time_boot_ms = mavlink_msg_debug_get_time_boot_ms(msg); - debug->value = mavlink_msg_debug_get_value(msg); - debug->ind = mavlink_msg_debug_get_ind(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DEBUG_LEN? msg->len : MAVLINK_MSG_ID_DEBUG_LEN; - memset(debug, 0, MAVLINK_MSG_ID_DEBUG_LEN); - memcpy(debug, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h b/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h deleted file mode 100644 index ac485af..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE DEBUG_VECT PACKING - -#define MAVLINK_MSG_ID_DEBUG_VECT 250 - -MAVPACKED( -typedef struct __mavlink_debug_vect_t { - uint64_t time_usec; /*< Timestamp*/ - float x; /*< x*/ - float y; /*< y*/ - float z; /*< z*/ - char name[10]; /*< Name*/ -}) mavlink_debug_vect_t; - -#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 -#define MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN 30 -#define MAVLINK_MSG_ID_250_LEN 30 -#define MAVLINK_MSG_ID_250_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ - 250, \ - "DEBUG_VECT", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ - "DEBUG_VECT", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ - } \ -} -#endif - -/** - * @brief Pack a debug_vect 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 name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *name, uint64_t time_usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - 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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -} - -/** - * @brief Pack a debug_vect message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *name,uint64_t time_usec,float x,float y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - 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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -} - -/** - * @brief Encode a debug_vect struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param debug_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) -{ - return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); -} - -/** - * @brief Encode a debug_vect struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param debug_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) -{ - return mavlink_msg_debug_vect_pack_chan(system_id, component_id, chan, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); -} - -/** - * @brief Send a debug_vect message - * @param chan MAVLink channel to send the message - * - * @param name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - 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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#endif -} - -/** - * @brief Send a debug_vect message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_debug_vect_send_struct(mavlink_channel_t chan, const mavlink_debug_vect_t* debug_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_debug_vect_send(chan, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)debug_vect, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DEBUG_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_debug_vect_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - mavlink_debug_vect_t *packet = (mavlink_debug_vect_t *)msgbuf; - packet->time_usec = time_usec; - packet->x = x; - 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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DEBUG_VECT UNPACKING - - -/** - * @brief Get field name from debug_vect message - * - * @return Name - */ -static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 20); -} - -/** - * @brief Get field time_usec from debug_vect message - * - * @return Timestamp - */ -static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from debug_vect message - * - * @return x - */ -static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from debug_vect message - * - * @return y - */ -static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from debug_vect message - * - * @return z - */ -static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a debug_vect message into a struct - * - * @param msg The message to decode - * @param debug_vect C-struct to decode the message contents into - */ -static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg); - debug_vect->x = mavlink_msg_debug_vect_get_x(msg); - debug_vect->y = mavlink_msg_debug_vect_get_y(msg); - debug_vect->z = mavlink_msg_debug_vect_get_z(msg); - mavlink_msg_debug_vect_get_name(msg, debug_vect->name); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DEBUG_VECT_LEN? msg->len : MAVLINK_MSG_ID_DEBUG_VECT_LEN; - memset(debug_vect, 0, MAVLINK_MSG_ID_DEBUG_VECT_LEN); - memcpy(debug_vect, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h b/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h deleted file mode 100644 index 2a52e69..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE DISTANCE_SENSOR PACKING - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR 132 - -MAVPACKED( -typedef struct __mavlink_distance_sensor_t { - uint32_t time_boot_ms; /*< Time since system boot*/ - uint16_t min_distance; /*< Minimum distance the sensor can measure in centimeters*/ - uint16_t max_distance; /*< Maximum distance the sensor can measure in centimeters*/ - uint16_t current_distance; /*< Current distance reading*/ - uint8_t type; /*< Type from MAV_DISTANCE_SENSOR enum.*/ - uint8_t id; /*< Onboard ID of the sensor*/ - uint8_t orientation; /*< Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.*/ - uint8_t covariance; /*< Measurement covariance in centimeters, 0 for unknown / invalid readings*/ -}) mavlink_distance_sensor_t; - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14 -#define MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN 14 -#define MAVLINK_MSG_ID_132_LEN 14 -#define MAVLINK_MSG_ID_132_MIN_LEN 14 - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85 -#define MAVLINK_MSG_ID_132_CRC 85 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \ - 132, \ - "DISTANCE_SENSOR", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \ - { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \ - { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \ - { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \ - { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \ - { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \ - "DISTANCE_SENSOR", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \ - { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \ - { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \ - { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \ - { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \ - { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \ - } \ -} -#endif - -/** - * @brief Pack a distance_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_boot_ms Time since system boot - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -} - -/** - * @brief Pack a distance_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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Time since system boot - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t type,uint8_t id,uint8_t orientation,uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -} - -/** - * @brief Encode a distance_sensor struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param distance_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) -{ - return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); -} - -/** - * @brief Encode a distance_sensor struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param distance_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) -{ - return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); -} - -/** - * @brief Send a distance_sensor message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Time since system boot - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#endif -} - -/** - * @brief Send a distance_sensor message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_distance_sensor_send_struct(mavlink_channel_t chan, const mavlink_distance_sensor_t* distance_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_distance_sensor_send(chan, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)distance_sensor, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->min_distance = min_distance; - packet->max_distance = max_distance; - packet->current_distance = current_distance; - packet->type = type; - packet->id = id; - packet->orientation = orientation; - packet->covariance = covariance; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DISTANCE_SENSOR UNPACKING - - -/** - * @brief Get field time_boot_ms from distance_sensor message - * - * @return Time since system boot - */ -static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field min_distance from distance_sensor message - * - * @return Minimum distance the sensor can measure in centimeters - */ -static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field max_distance from distance_sensor message - * - * @return Maximum distance the sensor can measure in centimeters - */ -static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field current_distance from distance_sensor message - * - * @return Current distance reading - */ -static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field type from distance_sensor message - * - * @return Type from MAV_DISTANCE_SENSOR enum. - */ -static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field id from distance_sensor message - * - * @return Onboard ID of the sensor - */ -static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field orientation from distance_sensor message - * - * @return Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - */ -static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field covariance from distance_sensor message - * - * @return Measurement covariance in centimeters, 0 for unknown / invalid readings - */ -static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Decode a distance_sensor message into a struct - * - * @param msg The message to decode - * @param distance_sensor C-struct to decode the message contents into - */ -static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* msg, mavlink_distance_sensor_t* distance_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - distance_sensor->time_boot_ms = mavlink_msg_distance_sensor_get_time_boot_ms(msg); - distance_sensor->min_distance = mavlink_msg_distance_sensor_get_min_distance(msg); - distance_sensor->max_distance = mavlink_msg_distance_sensor_get_max_distance(msg); - distance_sensor->current_distance = mavlink_msg_distance_sensor_get_current_distance(msg); - distance_sensor->type = mavlink_msg_distance_sensor_get_type(msg); - distance_sensor->id = mavlink_msg_distance_sensor_get_id(msg); - distance_sensor->orientation = mavlink_msg_distance_sensor_get_orientation(msg); - distance_sensor->covariance = mavlink_msg_distance_sensor_get_covariance(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN; - memset(distance_sensor, 0, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); - memcpy(distance_sensor, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h b/include/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h deleted file mode 100644 index 5e9bc92..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h +++ /dev/null @@ -1,230 +0,0 @@ -#pragma once -// MESSAGE ENCAPSULATED_DATA PACKING - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 131 - -MAVPACKED( -typedef struct __mavlink_encapsulated_data_t { - uint16_t seqnr; /*< sequence number (starting with 0 on every transmission)*/ - uint8_t data[253]; /*< image data bytes*/ -}) mavlink_encapsulated_data_t; - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255 -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN 255 -#define MAVLINK_MSG_ID_131_LEN 255 -#define MAVLINK_MSG_ID_131_MIN_LEN 255 - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223 -#define MAVLINK_MSG_ID_131_CRC 223 - -#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \ - 131, \ - "ENCAPSULATED_DATA", \ - 2, \ - { { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \ - "ENCAPSULATED_DATA", \ - 2, \ - { { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a encapsulated_data 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 seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seqnr, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -} - -/** - * @brief Pack a encapsulated_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seqnr,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -} - -/** - * @brief Encode a encapsulated_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param encapsulated_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) -{ - return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data); -} - -/** - * @brief Encode a encapsulated_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param encapsulated_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_encapsulated_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) -{ - return mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, chan, msg, encapsulated_data->seqnr, encapsulated_data->data); -} - -/** - * @brief Send a encapsulated_data message - * @param chan MAVLink channel to send the message - * - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#endif -} - -/** - * @brief Send a encapsulated_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_encapsulated_data_send_struct(mavlink_channel_t chan, const mavlink_encapsulated_data_t* encapsulated_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_encapsulated_data_send(chan, encapsulated_data->seqnr, encapsulated_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)encapsulated_data, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_encapsulated_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#else - mavlink_encapsulated_data_t *packet = (mavlink_encapsulated_data_t *)msgbuf; - 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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ENCAPSULATED_DATA UNPACKING - - -/** - * @brief Get field seqnr from encapsulated_data message - * - * @return sequence number (starting with 0 on every transmission) - */ -static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field data from encapsulated_data message - * - * @return image data bytes - */ -static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 253, 2); -} - -/** - * @brief Decode a encapsulated_data message into a struct - * - * @param msg The message to decode - * @param encapsulated_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg); - mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN? msg->len : MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN; - memset(encapsulated_data, 0, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); - memcpy(encapsulated_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_estimator_status.h b/include/mavlink/v1.0/common/mavlink_msg_estimator_status.h deleted file mode 100644 index 2b7c6c0..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_estimator_status.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE ESTIMATOR_STATUS PACKING - -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS 230 - -MAVPACKED( -typedef struct __mavlink_estimator_status_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float vel_ratio; /*< Velocity innovation test ratio*/ - float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/ - float pos_vert_ratio; /*< Vertical position innovation test ratio*/ - float mag_ratio; /*< Magnetometer innovation test ratio*/ - float hagl_ratio; /*< Height above terrain innovation test ratio*/ - float tas_ratio; /*< True airspeed innovation test ratio*/ - float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/ - float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/ - uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/ -}) mavlink_estimator_status_t; - -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN 42 -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN 42 -#define MAVLINK_MSG_ID_230_LEN 42 -#define MAVLINK_MSG_ID_230_MIN_LEN 42 - -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC 163 -#define MAVLINK_MSG_ID_230_CRC 163 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS { \ - 230, \ - "ESTIMATOR_STATUS", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \ - { "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \ - { "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \ - { "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \ - { "mag_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_estimator_status_t, mag_ratio) }, \ - { "hagl_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_estimator_status_t, hagl_ratio) }, \ - { "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \ - { "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \ - { "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS { \ - "ESTIMATOR_STATUS", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \ - { "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \ - { "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \ - { "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \ - { "mag_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_estimator_status_t, mag_ratio) }, \ - { "hagl_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_estimator_status_t, hagl_ratio) }, \ - { "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \ - { "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \ - { "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ - } \ -} -#endif - -/** - * @brief Pack a estimator_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 time_usec Timestamp (micros since boot or Unix epoch) - * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) - * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_estimator_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#else - mavlink_estimator_status_t packet; - packet.time_usec = time_usec; - packet.vel_ratio = vel_ratio; - packet.pos_horiz_ratio = pos_horiz_ratio; - packet.pos_vert_ratio = pos_vert_ratio; - packet.mag_ratio = mag_ratio; - packet.hagl_ratio = hagl_ratio; - packet.tas_ratio = tas_ratio; - packet.pos_horiz_accuracy = pos_horiz_accuracy; - packet.pos_vert_accuracy = pos_vert_accuracy; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ESTIMATOR_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -} - -/** - * @brief Pack a estimator_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) - * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_estimator_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint16_t flags,float vel_ratio,float pos_horiz_ratio,float pos_vert_ratio,float mag_ratio,float hagl_ratio,float tas_ratio,float pos_horiz_accuracy,float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#else - mavlink_estimator_status_t packet; - packet.time_usec = time_usec; - packet.vel_ratio = vel_ratio; - packet.pos_horiz_ratio = pos_horiz_ratio; - packet.pos_vert_ratio = pos_vert_ratio; - packet.mag_ratio = mag_ratio; - packet.hagl_ratio = hagl_ratio; - packet.tas_ratio = tas_ratio; - packet.pos_horiz_accuracy = pos_horiz_accuracy; - packet.pos_vert_accuracy = pos_vert_accuracy; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ESTIMATOR_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -} - -/** - * @brief Encode a estimator_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param estimator_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_estimator_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_estimator_status_t* estimator_status) -{ - return mavlink_msg_estimator_status_pack(system_id, component_id, msg, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); -} - -/** - * @brief Encode a estimator_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param estimator_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_estimator_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_estimator_status_t* estimator_status) -{ - return mavlink_msg_estimator_status_pack_chan(system_id, component_id, chan, msg, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); -} - -/** - * @brief Send a estimator_status message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) - * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_estimator_status_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#else - mavlink_estimator_status_t packet; - packet.time_usec = time_usec; - packet.vel_ratio = vel_ratio; - packet.pos_horiz_ratio = pos_horiz_ratio; - packet.pos_vert_ratio = pos_vert_ratio; - packet.mag_ratio = mag_ratio; - packet.hagl_ratio = hagl_ratio; - packet.tas_ratio = tas_ratio; - packet.pos_horiz_accuracy = pos_horiz_accuracy; - packet.pos_vert_accuracy = pos_vert_accuracy; - packet.flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#endif -} - -/** - * @brief Send a estimator_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_estimator_status_send_struct(mavlink_channel_t chan, const mavlink_estimator_status_t* estimator_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_estimator_status_send(chan, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)estimator_status, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_estimator_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#else - mavlink_estimator_status_t *packet = (mavlink_estimator_status_t *)msgbuf; - packet->time_usec = time_usec; - packet->vel_ratio = vel_ratio; - packet->pos_horiz_ratio = pos_horiz_ratio; - packet->pos_vert_ratio = pos_vert_ratio; - packet->mag_ratio = mag_ratio; - packet->hagl_ratio = hagl_ratio; - packet->tas_ratio = tas_ratio; - packet->pos_horiz_accuracy = pos_horiz_accuracy; - packet->pos_vert_accuracy = pos_vert_accuracy; - packet->flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ESTIMATOR_STATUS UNPACKING - - -/** - * @brief Get field time_usec from estimator_status message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_estimator_status_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field flags from estimator_status message - * - * @return Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - */ -static inline uint16_t mavlink_msg_estimator_status_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 40); -} - -/** - * @brief Get field vel_ratio from estimator_status message - * - * @return Velocity innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_vel_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pos_horiz_ratio from estimator_status message - * - * @return Horizontal position innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_pos_horiz_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field pos_vert_ratio from estimator_status message - * - * @return Vertical position innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_pos_vert_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field mag_ratio from estimator_status message - * - * @return Magnetometer innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_mag_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field hagl_ratio from estimator_status message - * - * @return Height above terrain innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_hagl_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field tas_ratio from estimator_status message - * - * @return True airspeed innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_tas_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field pos_horiz_accuracy from estimator_status message - * - * @return Horizontal position 1-STD accuracy relative to the EKF local origin (m) - */ -static inline float mavlink_msg_estimator_status_get_pos_horiz_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field pos_vert_accuracy from estimator_status message - * - * @return Vertical position 1-STD accuracy relative to the EKF local origin (m) - */ -static inline float mavlink_msg_estimator_status_get_pos_vert_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a estimator_status message into a struct - * - * @param msg The message to decode - * @param estimator_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_estimator_status_decode(const mavlink_message_t* msg, mavlink_estimator_status_t* estimator_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - estimator_status->time_usec = mavlink_msg_estimator_status_get_time_usec(msg); - estimator_status->vel_ratio = mavlink_msg_estimator_status_get_vel_ratio(msg); - estimator_status->pos_horiz_ratio = mavlink_msg_estimator_status_get_pos_horiz_ratio(msg); - estimator_status->pos_vert_ratio = mavlink_msg_estimator_status_get_pos_vert_ratio(msg); - estimator_status->mag_ratio = mavlink_msg_estimator_status_get_mag_ratio(msg); - estimator_status->hagl_ratio = mavlink_msg_estimator_status_get_hagl_ratio(msg); - estimator_status->tas_ratio = mavlink_msg_estimator_status_get_tas_ratio(msg); - estimator_status->pos_horiz_accuracy = mavlink_msg_estimator_status_get_pos_horiz_accuracy(msg); - estimator_status->pos_vert_accuracy = mavlink_msg_estimator_status_get_pos_vert_accuracy(msg); - estimator_status->flags = mavlink_msg_estimator_status_get_flags(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN; - memset(estimator_status, 0, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); - memcpy(estimator_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_extended_sys_state.h b/include/mavlink/v1.0/common/mavlink_msg_extended_sys_state.h deleted file mode 100644 index 329a774..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_extended_sys_state.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE EXTENDED_SYS_STATE PACKING - -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE 245 - -MAVPACKED( -typedef struct __mavlink_extended_sys_state_t { - uint8_t vtol_state; /*< The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.*/ - uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ -}) mavlink_extended_sys_state_t; - -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN 2 -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN 2 -#define MAVLINK_MSG_ID_245_LEN 2 -#define MAVLINK_MSG_ID_245_MIN_LEN 2 - -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC 130 -#define MAVLINK_MSG_ID_245_CRC 130 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE { \ - 245, \ - "EXTENDED_SYS_STATE", \ - 2, \ - { { "vtol_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_sys_state_t, vtol_state) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_sys_state_t, landed_state) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE { \ - "EXTENDED_SYS_STATE", \ - 2, \ - { { "vtol_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_sys_state_t, vtol_state) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_sys_state_t, landed_state) }, \ - } \ -} -#endif - -/** - * @brief Pack a extended_sys_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 vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_extended_sys_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t vtol_state, uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#else - mavlink_extended_sys_state_t packet; - packet.vtol_state = vtol_state; - packet.landed_state = landed_state; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -} - -/** - * @brief Pack a extended_sys_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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_extended_sys_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t vtol_state,uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#else - mavlink_extended_sys_state_t packet; - packet.vtol_state = vtol_state; - packet.landed_state = landed_state; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -} - -/** - * @brief Encode a extended_sys_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param extended_sys_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_extended_sys_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state) -{ - return mavlink_msg_extended_sys_state_pack(system_id, component_id, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state); -} - -/** - * @brief Encode a extended_sys_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param extended_sys_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_extended_sys_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state) -{ - return mavlink_msg_extended_sys_state_pack_chan(system_id, component_id, chan, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state); -} - -/** - * @brief Send a extended_sys_state message - * @param chan MAVLink channel to send the message - * - * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_extended_sys_state_send(mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#else - mavlink_extended_sys_state_t packet; - packet.vtol_state = vtol_state; - packet.landed_state = landed_state; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)&packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#endif -} - -/** - * @brief Send a extended_sys_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_extended_sys_state_send_struct(mavlink_channel_t chan, const mavlink_extended_sys_state_t* extended_sys_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_extended_sys_state_send(chan, extended_sys_state->vtol_state, extended_sys_state->landed_state); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)extended_sys_state, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_extended_sys_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#else - mavlink_extended_sys_state_t *packet = (mavlink_extended_sys_state_t *)msgbuf; - packet->vtol_state = vtol_state; - packet->landed_state = landed_state; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE EXTENDED_SYS_STATE UNPACKING - - -/** - * @brief Get field vtol_state from extended_sys_state message - * - * @return The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - */ -static inline uint8_t mavlink_msg_extended_sys_state_get_vtol_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field landed_state from extended_sys_state message - * - * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - */ -static inline uint8_t mavlink_msg_extended_sys_state_get_landed_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a extended_sys_state message into a struct - * - * @param msg The message to decode - * @param extended_sys_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_extended_sys_state_decode(const mavlink_message_t* msg, mavlink_extended_sys_state_t* extended_sys_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - extended_sys_state->vtol_state = mavlink_msg_extended_sys_state_get_vtol_state(msg); - extended_sys_state->landed_state = mavlink_msg_extended_sys_state_get_landed_state(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN? msg->len : MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN; - memset(extended_sys_state, 0, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); - memcpy(extended_sys_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_file_transfer_protocol.h b/include/mavlink/v1.0/common/mavlink_msg_file_transfer_protocol.h deleted file mode 100644 index 07b5a3e..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_file_transfer_protocol.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE FILE_TRANSFER_PROTOCOL PACKING - -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 110 - -MAVPACKED( -typedef struct __mavlink_file_transfer_protocol_t { - uint8_t target_network; /*< Network ID (0 for broadcast)*/ - uint8_t target_system; /*< System ID (0 for broadcast)*/ - uint8_t target_component; /*< Component ID (0 for broadcast)*/ - uint8_t payload[251]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/ -}) mavlink_file_transfer_protocol_t; - -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254 -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN 254 -#define MAVLINK_MSG_ID_110_LEN 254 -#define MAVLINK_MSG_ID_110_MIN_LEN 254 - -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC 84 -#define MAVLINK_MSG_ID_110_CRC 84 - -#define MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN 251 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL { \ - 110, \ - "FILE_TRANSFER_PROTOCOL", \ - 4, \ - { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL { \ - "FILE_TRANSFER_PROTOCOL", \ - 4, \ - { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \ - } \ -} -#endif - -/** - * @brief Pack a file_transfer_protocol message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#else - mavlink_file_transfer_protocol_t packet; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -} - -/** - * @brief Pack a file_transfer_protocol message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_network,uint8_t target_system,uint8_t target_component,const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#else - mavlink_file_transfer_protocol_t packet; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -} - -/** - * @brief Encode a file_transfer_protocol struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param file_transfer_protocol C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ - return mavlink_msg_file_transfer_protocol_pack(system_id, component_id, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); -} - -/** - * @brief Encode a file_transfer_protocol struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param file_transfer_protocol C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ - return mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, chan, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); -} - -/** - * @brief Send a file_transfer_protocol message - * @param chan MAVLink channel to send the message - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_file_transfer_protocol_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#else - mavlink_file_transfer_protocol_t packet; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#endif -} - -/** - * @brief Send a file_transfer_protocol message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_file_transfer_protocol_send_struct(mavlink_channel_t chan, const mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_file_transfer_protocol_send(chan, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)file_transfer_protocol, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_file_transfer_protocol_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#else - mavlink_file_transfer_protocol_t *packet = (mavlink_file_transfer_protocol_t *)msgbuf; - packet->target_network = target_network; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE FILE_TRANSFER_PROTOCOL UNPACKING - - -/** - * @brief Get field target_network from file_transfer_protocol message - * - * @return Network ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_network(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_system from file_transfer_protocol message - * - * @return System ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field target_component from file_transfer_protocol message - * - * @return Component ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field payload from file_transfer_protocol message - * - * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_get_payload(const mavlink_message_t* msg, uint8_t *payload) -{ - return _MAV_RETURN_uint8_t_array(msg, payload, 251, 3); -} - -/** - * @brief Decode a file_transfer_protocol message into a struct - * - * @param msg The message to decode - * @param file_transfer_protocol C-struct to decode the message contents into - */ -static inline void mavlink_msg_file_transfer_protocol_decode(const mavlink_message_t* msg, mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - file_transfer_protocol->target_network = mavlink_msg_file_transfer_protocol_get_target_network(msg); - file_transfer_protocol->target_system = mavlink_msg_file_transfer_protocol_get_target_system(msg); - file_transfer_protocol->target_component = mavlink_msg_file_transfer_protocol_get_target_component(msg); - mavlink_msg_file_transfer_protocol_get_payload(msg, file_transfer_protocol->payload); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN? msg->len : MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN; - memset(file_transfer_protocol, 0, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); - memcpy(file_transfer_protocol, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_follow_target.h b/include/mavlink/v1.0/common/mavlink_msg_follow_target.h deleted file mode 100644 index bfd45f6..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_follow_target.h +++ /dev/null @@ -1,459 +0,0 @@ -#pragma once -// MESSAGE FOLLOW_TARGET PACKING - -#define MAVLINK_MSG_ID_FOLLOW_TARGET 144 - -MAVPACKED( -typedef struct __mavlink_follow_target_t { - uint64_t timestamp; /*< Timestamp in milliseconds since system boot*/ - uint64_t custom_state; /*< button states or switches of a tracker device*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - float alt; /*< AMSL, in meters*/ - float vel[3]; /*< target velocity (0,0,0) for unknown*/ - float acc[3]; /*< linear target acceleration (0,0,0) for unknown*/ - float attitude_q[4]; /*< (1 0 0 0 for unknown)*/ - float rates[3]; /*< (0 0 0 for unknown)*/ - float position_cov[3]; /*< eph epv*/ - uint8_t est_capabilities; /*< bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)*/ -}) mavlink_follow_target_t; - -#define MAVLINK_MSG_ID_FOLLOW_TARGET_LEN 93 -#define MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN 93 -#define MAVLINK_MSG_ID_144_LEN 93 -#define MAVLINK_MSG_ID_144_MIN_LEN 93 - -#define MAVLINK_MSG_ID_FOLLOW_TARGET_CRC 127 -#define MAVLINK_MSG_ID_144_CRC 127 - -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_VEL_LEN 3 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ACC_LEN 3 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ATTITUDE_Q_LEN 4 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_RATES_LEN 3 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_POSITION_COV_LEN 3 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_FOLLOW_TARGET { \ - 144, \ - "FOLLOW_TARGET", \ - 11, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \ - { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \ - { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_follow_target_t, vel) }, \ - { "acc", NULL, MAVLINK_TYPE_FLOAT, 3, 40, offsetof(mavlink_follow_target_t, acc) }, \ - { "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \ - { "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \ - { "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \ - { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_FOLLOW_TARGET { \ - "FOLLOW_TARGET", \ - 11, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \ - { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \ - { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_follow_target_t, vel) }, \ - { "acc", NULL, MAVLINK_TYPE_FLOAT, 3, 40, offsetof(mavlink_follow_target_t, acc) }, \ - { "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \ - { "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \ - { "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \ - { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ - } \ -} -#endif - -/** - * @brief Pack a follow_target message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param timestamp Timestamp in milliseconds since system boot - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt AMSL, in meters - * @param vel target velocity (0,0,0) for unknown - * @param acc linear target acceleration (0,0,0) for unknown - * @param attitude_q (1 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_follow_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#else - mavlink_follow_target_t packet; - packet.timestamp = timestamp; - packet.custom_state = custom_state; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.est_capabilities = est_capabilities; - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - mav_array_memcpy(packet.acc, acc, sizeof(float)*3); - mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet.rates, rates, sizeof(float)*3); - mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FOLLOW_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -} - -/** - * @brief Pack a follow_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param timestamp Timestamp in milliseconds since system boot - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt AMSL, in meters - * @param vel target velocity (0,0,0) for unknown - * @param acc linear target acceleration (0,0,0) for unknown - * @param attitude_q (1 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_follow_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t timestamp,uint8_t est_capabilities,int32_t lat,int32_t lon,float alt,const float *vel,const float *acc,const float *attitude_q,const float *rates,const float *position_cov,uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#else - mavlink_follow_target_t packet; - packet.timestamp = timestamp; - packet.custom_state = custom_state; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.est_capabilities = est_capabilities; - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - mav_array_memcpy(packet.acc, acc, sizeof(float)*3); - mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet.rates, rates, sizeof(float)*3); - mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FOLLOW_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -} - -/** - * @brief Encode a follow_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param follow_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_follow_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_follow_target_t* follow_target) -{ - return mavlink_msg_follow_target_pack(system_id, component_id, msg, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); -} - -/** - * @brief Encode a follow_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param follow_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_follow_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_follow_target_t* follow_target) -{ - return mavlink_msg_follow_target_pack_chan(system_id, component_id, chan, msg, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); -} - -/** - * @brief Send a follow_target message - * @param chan MAVLink channel to send the message - * - * @param timestamp Timestamp in milliseconds since system boot - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt AMSL, in meters - * @param vel target velocity (0,0,0) for unknown - * @param acc linear target acceleration (0,0,0) for unknown - * @param attitude_q (1 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_follow_target_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#else - mavlink_follow_target_t packet; - packet.timestamp = timestamp; - packet.custom_state = custom_state; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.est_capabilities = est_capabilities; - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - mav_array_memcpy(packet.acc, acc, sizeof(float)*3); - mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet.rates, rates, sizeof(float)*3); - mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)&packet, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#endif -} - -/** - * @brief Send a follow_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_follow_target_send_struct(mavlink_channel_t chan, const mavlink_follow_target_t* follow_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_follow_target_send(chan, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)follow_target, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_FOLLOW_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_follow_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#else - mavlink_follow_target_t *packet = (mavlink_follow_target_t *)msgbuf; - packet->timestamp = timestamp; - packet->custom_state = custom_state; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->est_capabilities = est_capabilities; - mav_array_memcpy(packet->vel, vel, sizeof(float)*3); - mav_array_memcpy(packet->acc, acc, sizeof(float)*3); - mav_array_memcpy(packet->attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet->rates, rates, sizeof(float)*3); - mav_array_memcpy(packet->position_cov, position_cov, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)packet, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE FOLLOW_TARGET UNPACKING - - -/** - * @brief Get field timestamp from follow_target message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint64_t mavlink_msg_follow_target_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field est_capabilities from follow_target message - * - * @return bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - */ -static inline uint8_t mavlink_msg_follow_target_get_est_capabilities(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 92); -} - -/** - * @brief Get field lat from follow_target message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_follow_target_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field lon from follow_target message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_follow_target_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field alt from follow_target message - * - * @return AMSL, in meters - */ -static inline float mavlink_msg_follow_target_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vel from follow_target message - * - * @return target velocity (0,0,0) for unknown - */ -static inline uint16_t mavlink_msg_follow_target_get_vel(const mavlink_message_t* msg, float *vel) -{ - return _MAV_RETURN_float_array(msg, vel, 3, 28); -} - -/** - * @brief Get field acc from follow_target message - * - * @return linear target acceleration (0,0,0) for unknown - */ -static inline uint16_t mavlink_msg_follow_target_get_acc(const mavlink_message_t* msg, float *acc) -{ - return _MAV_RETURN_float_array(msg, acc, 3, 40); -} - -/** - * @brief Get field attitude_q from follow_target message - * - * @return (1 0 0 0 for unknown) - */ -static inline uint16_t mavlink_msg_follow_target_get_attitude_q(const mavlink_message_t* msg, float *attitude_q) -{ - return _MAV_RETURN_float_array(msg, attitude_q, 4, 52); -} - -/** - * @brief Get field rates from follow_target message - * - * @return (0 0 0 for unknown) - */ -static inline uint16_t mavlink_msg_follow_target_get_rates(const mavlink_message_t* msg, float *rates) -{ - return _MAV_RETURN_float_array(msg, rates, 3, 68); -} - -/** - * @brief Get field position_cov from follow_target message - * - * @return eph epv - */ -static inline uint16_t mavlink_msg_follow_target_get_position_cov(const mavlink_message_t* msg, float *position_cov) -{ - return _MAV_RETURN_float_array(msg, position_cov, 3, 80); -} - -/** - * @brief Get field custom_state from follow_target message - * - * @return button states or switches of a tracker device - */ -static inline uint64_t mavlink_msg_follow_target_get_custom_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Decode a follow_target message into a struct - * - * @param msg The message to decode - * @param follow_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_follow_target_decode(const mavlink_message_t* msg, mavlink_follow_target_t* follow_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - follow_target->timestamp = mavlink_msg_follow_target_get_timestamp(msg); - follow_target->custom_state = mavlink_msg_follow_target_get_custom_state(msg); - follow_target->lat = mavlink_msg_follow_target_get_lat(msg); - follow_target->lon = mavlink_msg_follow_target_get_lon(msg); - follow_target->alt = mavlink_msg_follow_target_get_alt(msg); - mavlink_msg_follow_target_get_vel(msg, follow_target->vel); - mavlink_msg_follow_target_get_acc(msg, follow_target->acc); - mavlink_msg_follow_target_get_attitude_q(msg, follow_target->attitude_q); - mavlink_msg_follow_target_get_rates(msg, follow_target->rates); - mavlink_msg_follow_target_get_position_cov(msg, follow_target->position_cov); - follow_target->est_capabilities = mavlink_msg_follow_target_get_est_capabilities(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_FOLLOW_TARGET_LEN? msg->len : MAVLINK_MSG_ID_FOLLOW_TARGET_LEN; - memset(follow_target, 0, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); - memcpy(follow_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h b/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h deleted file mode 100644 index ef6267d..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h +++ /dev/null @@ -1,413 +0,0 @@ -#pragma once -// MESSAGE GLOBAL_POSITION_INT PACKING - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 - -MAVPACKED( -typedef struct __mavlink_global_position_int_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ - int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)*/ - int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/ - int16_t vx; /*< Ground X Speed (Latitude, positive north), expressed as m/s * 100*/ - int16_t vy; /*< Ground Y Speed (Longitude, positive east), expressed as m/s * 100*/ - int16_t vz; /*< Ground Z Speed (Altitude, positive down), expressed as m/s * 100*/ - uint16_t hdg; /*< Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ -}) mavlink_global_position_int_t; - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN 28 -#define MAVLINK_MSG_ID_33_LEN 28 -#define MAVLINK_MSG_ID_33_MIN_LEN 28 - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104 -#define MAVLINK_MSG_ID_33_CRC 104 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ - 33, \ - "GLOBAL_POSITION_INT", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \ - { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ - "GLOBAL_POSITION_INT", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \ - { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \ - } \ -} -#endif - -/** - * @brief Pack a global_position_int 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_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - - 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; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - - 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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -} - -/** - * @brief Pack a global_position_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - - 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; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - - 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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -} - -/** - * @brief Encode a global_position_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_position_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) -{ - return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); -} - -/** - * @brief Encode a global_position_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_position_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) -{ - return mavlink_msg_global_position_int_pack_chan(system_id, component_id, chan, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); -} - -/** - * @brief Send a global_position_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - mavlink_global_position_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#endif -} - -/** - * @brief Send a global_position_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_global_position_int_send_struct(mavlink_channel_t chan, const mavlink_global_position_int_t* global_position_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_global_position_int_send(chan, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)global_position_int, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - mavlink_global_position_int_t *packet = (mavlink_global_position_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->relative_alt = relative_alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->hdg = hdg; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_POSITION_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from global_position_int message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field lat from global_position_int message - * - * @return Latitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon from global_position_int message - * - * @return Longitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt from global_position_int message - * - * @return Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - */ -static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field relative_alt from global_position_int message - * - * @return Altitude above ground in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field vx from global_position_int message - * - * @return Ground X Speed (Latitude, positive north), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field vy from global_position_int message - * - * @return Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field vz from global_position_int message - * - * @return Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 24); -} - -/** - * @brief Get field hdg from global_position_int message - * - * @return Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Decode a global_position_int message into a struct - * - * @param msg The message to decode - * @param global_position_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg); - global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg); - global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg); - global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg); - global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg); - global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg); - global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN; - memset(global_position_int, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); - memcpy(global_position_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_global_position_int_cov.h b/include/mavlink/v1.0/common/mavlink_msg_global_position_int_cov.h deleted file mode 100644 index 0d33faf..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_global_position_int_cov.h +++ /dev/null @@ -1,430 +0,0 @@ -#pragma once -// MESSAGE GLOBAL_POSITION_INT_COV PACKING - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63 - -MAVPACKED( -typedef struct __mavlink_global_position_int_cov_t { - uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/ - int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ - int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), above MSL*/ - int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/ - float vx; /*< Ground X Speed (Latitude), expressed as m/s*/ - float vy; /*< Ground Y Speed (Longitude), expressed as m/s*/ - float vz; /*< Ground Z Speed (Altitude), expressed as m/s*/ - float covariance[36]; /*< Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)*/ - uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ -}) mavlink_global_position_int_cov_t; - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 181 -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN 181 -#define MAVLINK_MSG_ID_63_LEN 181 -#define MAVLINK_MSG_ID_63_MIN_LEN 181 - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 119 -#define MAVLINK_MSG_ID_63_CRC 119 - -#define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \ - 63, \ - "GLOBAL_POSITION_INT_COV", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_int_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \ - "GLOBAL_POSITION_INT_COV", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_int_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a global_position_int_cov 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 since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s - * @param vy Ground Y Speed (Longitude), expressed as m/s - * @param vz Ground Z Speed (Altitude), expressed as m/s - * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#else - mavlink_global_position_int_cov_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -} - -/** - * @brief Pack a global_position_int_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s - * @param vy Ground Y Speed (Longitude), expressed as m/s - * @param vz Ground Z Speed (Altitude), expressed as m/s - * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t estimator_type,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,float vx,float vy,float vz,const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#else - mavlink_global_position_int_cov_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -} - -/** - * @brief Encode a global_position_int_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_position_int_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov) -{ - return mavlink_msg_global_position_int_cov_pack(system_id, component_id, msg, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); -} - -/** - * @brief Encode a global_position_int_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_position_int_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov) -{ - return mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, chan, msg, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); -} - -/** - * @brief Send a global_position_int_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s - * @param vy Ground Y Speed (Longitude), expressed as m/s - * @param vz Ground Z Speed (Altitude), expressed as m/s - * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_global_position_int_cov_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#else - mavlink_global_position_int_cov_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#endif -} - -/** - * @brief Send a global_position_int_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_global_position_int_cov_send_struct(mavlink_channel_t chan, const mavlink_global_position_int_cov_t* global_position_int_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_global_position_int_cov_send(chan, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)global_position_int_cov, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#else - mavlink_global_position_int_cov_t *packet = (mavlink_global_position_int_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->relative_alt = relative_alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->estimator_type = estimator_type; - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_POSITION_INT_COV UNPACKING - - -/** - * @brief Get field time_usec from global_position_int_cov message - * - * @return Timestamp (microseconds since system boot or since UNIX epoch) - */ -static inline uint64_t mavlink_msg_global_position_int_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field estimator_type from global_position_int_cov message - * - * @return Class id of the estimator this estimate originated from. - */ -static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 180); -} - -/** - * @brief Get field lat from global_position_int_cov message - * - * @return Latitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from global_position_int_cov message - * - * @return Longitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from global_position_int_cov message - * - * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field relative_alt from global_position_int_cov message - * - * @return Altitude above ground in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field vx from global_position_int_cov message - * - * @return Ground X Speed (Latitude), expressed as m/s - */ -static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vy from global_position_int_cov message - * - * @return Ground Y Speed (Longitude), expressed as m/s - */ -static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field vz from global_position_int_cov message - * - * @return Ground Z Speed (Altitude), expressed as m/s - */ -static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field covariance from global_position_int_cov message - * - * @return Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) - */ -static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 36, 36); -} - -/** - * @brief Decode a global_position_int_cov message into a struct - * - * @param msg The message to decode - * @param global_position_int_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_position_int_cov_decode(const mavlink_message_t* msg, mavlink_global_position_int_cov_t* global_position_int_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - global_position_int_cov->time_usec = mavlink_msg_global_position_int_cov_get_time_usec(msg); - global_position_int_cov->lat = mavlink_msg_global_position_int_cov_get_lat(msg); - global_position_int_cov->lon = mavlink_msg_global_position_int_cov_get_lon(msg); - global_position_int_cov->alt = mavlink_msg_global_position_int_cov_get_alt(msg); - global_position_int_cov->relative_alt = mavlink_msg_global_position_int_cov_get_relative_alt(msg); - global_position_int_cov->vx = mavlink_msg_global_position_int_cov_get_vx(msg); - global_position_int_cov->vy = mavlink_msg_global_position_int_cov_get_vy(msg); - global_position_int_cov->vz = mavlink_msg_global_position_int_cov_get_vz(msg); - mavlink_msg_global_position_int_cov_get_covariance(msg, global_position_int_cov->covariance); - global_position_int_cov->estimator_type = mavlink_msg_global_position_int_cov_get_estimator_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN; - memset(global_position_int_cov, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); - memcpy(global_position_int_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h b/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h deleted file mode 100644 index 6b65eb0..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101 - -MAVPACKED( -typedef struct __mavlink_global_vision_position_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X position*/ - float y; /*< Global Y position*/ - float z; /*< Global Z position*/ - float roll; /*< Roll angle in rad*/ - float pitch; /*< Pitch angle in rad*/ - float yaw; /*< Yaw angle in rad*/ -}) mavlink_global_vision_position_estimate_t; - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32 -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN 32 -#define MAVLINK_MSG_ID_101_LEN 32 -#define MAVLINK_MSG_ID_101_MIN_LEN 32 - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102 -#define MAVLINK_MSG_ID_101_CRC 102 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ - 101, \ - "GLOBAL_VISION_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ - "GLOBAL_VISION_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a global_vision_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Pack a global_vision_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Encode a global_vision_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ - return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); -} - -/** - * @brief Encode a global_vision_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ - return mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); -} - -/** - * @brief Send a global_vision_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_global_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a global_vision_position_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_global_vision_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_global_vision_position_estimate_send(chan, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)global_vision_position_estimate, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_global_vision_position_estimate_t *packet = (mavlink_global_vision_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from global_vision_position_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from global_vision_position_estimate message - * - * @return Global X position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from global_vision_position_estimate message - * - * @return Global Y position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from global_vision_position_estimate message - * - * @return Global Z position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from global_vision_position_estimate message - * - * @return Roll angle in rad - */ -static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from global_vision_position_estimate message - * - * @return Pitch angle in rad - */ -static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from global_vision_position_estimate message - * - * @return Yaw angle in rad - */ -static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a global_vision_position_estimate message into a struct - * - * @param msg The message to decode - * @param global_vision_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - global_vision_position_estimate->usec = mavlink_msg_global_vision_position_estimate_get_usec(msg); - global_vision_position_estimate->x = mavlink_msg_global_vision_position_estimate_get_x(msg); - global_vision_position_estimate->y = mavlink_msg_global_vision_position_estimate_get_y(msg); - global_vision_position_estimate->z = mavlink_msg_global_vision_position_estimate_get_z(msg); - global_vision_position_estimate->roll = mavlink_msg_global_vision_position_estimate_get_roll(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN; - memset(global_vision_position_estimate, 0, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); - memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h b/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h deleted file mode 100644 index aeccc4e..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h +++ /dev/null @@ -1,488 +0,0 @@ -#pragma once -// MESSAGE GPS2_RAW PACKING - -#define MAVLINK_MSG_ID_GPS2_RAW 124 - -MAVPACKED( -typedef struct __mavlink_gps2_raw_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/ - uint32_t dgps_age; /*< Age of DGPS info*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/ - uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/ - uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ - uint8_t fix_type; /*< See the GPS_FIX_TYPE enum.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ - uint8_t dgps_numch; /*< Number of DGPS satellites*/ -}) mavlink_gps2_raw_t; - -#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35 -#define MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN 35 -#define MAVLINK_MSG_ID_124_LEN 35 -#define MAVLINK_MSG_ID_124_MIN_LEN 35 - -#define MAVLINK_MSG_ID_GPS2_RAW_CRC 87 -#define MAVLINK_MSG_ID_124_CRC 87 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \ - 124, \ - "GPS2_RAW", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \ - { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \ - { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \ - "GPS2_RAW", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \ - { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \ - { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps2_raw 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 since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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, uint8_t dgps_numch, uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -} - -/** - * @brief Pack a gps2_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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,uint8_t dgps_numch,uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -} - -/** - * @brief Encode a gps2_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps2_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) -{ - return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); -} - -/** - * @brief Encode a gps2_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps2_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) -{ - return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); -} - -/** - * @brief Send a gps2_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps2_raw_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, uint8_t dgps_numch, uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#endif -} - -/** - * @brief Send a gps2_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps2_raw_send_struct(mavlink_channel_t chan, const mavlink_gps2_raw_t* gps2_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps2_raw_send(chan, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)gps2_raw, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, 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, uint8_t dgps_numch, uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->dgps_age = dgps_age; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->cog = cog; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - packet->dgps_numch = dgps_numch; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS2_RAW UNPACKING - - -/** - * @brief Get field time_usec from gps2_raw message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from gps2_raw message - * - * @return See the GPS_FIX_TYPE enum. - */ -static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field lat from gps2_raw message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from gps2_raw message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from gps2_raw message - * - * @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from gps2_raw message - * - * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field epv from gps2_raw message - * - * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field vel from gps2_raw message - * - * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field cog from gps2_raw message - * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field satellites_visible from gps2_raw message - * - * @return Number of satellites visible. If unknown, set to 255 - */ -static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field dgps_numch from gps2_raw message - * - * @return Number of DGPS satellites - */ -static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field dgps_age from gps2_raw message - * - * @return Age of DGPS info - */ -static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Decode a gps2_raw message into a struct - * - * @param msg The message to decode - * @param gps2_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps2_raw->time_usec = mavlink_msg_gps2_raw_get_time_usec(msg); - gps2_raw->lat = mavlink_msg_gps2_raw_get_lat(msg); - gps2_raw->lon = mavlink_msg_gps2_raw_get_lon(msg); - gps2_raw->alt = mavlink_msg_gps2_raw_get_alt(msg); - gps2_raw->dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg); - gps2_raw->eph = mavlink_msg_gps2_raw_get_eph(msg); - gps2_raw->epv = mavlink_msg_gps2_raw_get_epv(msg); - gps2_raw->vel = mavlink_msg_gps2_raw_get_vel(msg); - gps2_raw->cog = mavlink_msg_gps2_raw_get_cog(msg); - gps2_raw->fix_type = mavlink_msg_gps2_raw_get_fix_type(msg); - gps2_raw->satellites_visible = mavlink_msg_gps2_raw_get_satellites_visible(msg); - gps2_raw->dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS2_RAW_LEN? msg->len : MAVLINK_MSG_ID_GPS2_RAW_LEN; - memset(gps2_raw, 0, MAVLINK_MSG_ID_GPS2_RAW_LEN); - memcpy(gps2_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h b/include/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h deleted file mode 100644 index e383647..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE GPS2_RTK PACKING - -#define MAVLINK_MSG_ID_GPS2_RTK 128 - -MAVPACKED( -typedef struct __mavlink_gps2_rtk_t { - uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/ - uint32_t tow; /*< GPS Time of Week of last baseline*/ - int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/ - int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/ - int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/ - uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ - int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ - uint16_t wn; /*< GPS Week Number of last baseline*/ - uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ - uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ - uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/ - uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ - uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/ -}) mavlink_gps2_rtk_t; - -#define MAVLINK_MSG_ID_GPS2_RTK_LEN 35 -#define MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN 35 -#define MAVLINK_MSG_ID_128_LEN 35 -#define MAVLINK_MSG_ID_128_MIN_LEN 35 - -#define MAVLINK_MSG_ID_GPS2_RTK_CRC 226 -#define MAVLINK_MSG_ID_128_CRC 226 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS2_RTK { \ - 128, \ - "GPS2_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS2_RTK { \ - "GPS2_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps2_rtk 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_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#else - mavlink_gps2_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -} - -/** - * @brief Pack a gps2_rtk message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#else - mavlink_gps2_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -} - -/** - * @brief Encode a gps2_rtk struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps2_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) -{ - return mavlink_msg_gps2_rtk_pack(system_id, component_id, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); -} - -/** - * @brief Encode a gps2_rtk struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps2_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) -{ - return mavlink_msg_gps2_rtk_pack_chan(system_id, component_id, chan, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); -} - -/** - * @brief Send a gps2_rtk message - * @param chan MAVLink channel to send the message - * - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps2_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#else - mavlink_gps2_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#endif -} - -/** - * @brief Send a gps2_rtk message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps2_rtk_send_struct(mavlink_channel_t chan, const mavlink_gps2_rtk_t* gps2_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps2_rtk_send(chan, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)gps2_rtk, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS2_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps2_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#else - mavlink_gps2_rtk_t *packet = (mavlink_gps2_rtk_t *)msgbuf; - packet->time_last_baseline_ms = time_last_baseline_ms; - packet->tow = tow; - packet->baseline_a_mm = baseline_a_mm; - packet->baseline_b_mm = baseline_b_mm; - packet->baseline_c_mm = baseline_c_mm; - packet->accuracy = accuracy; - packet->iar_num_hypotheses = iar_num_hypotheses; - packet->wn = wn; - packet->rtk_receiver_id = rtk_receiver_id; - packet->rtk_health = rtk_health; - packet->rtk_rate = rtk_rate; - packet->nsats = nsats; - packet->baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS2_RTK UNPACKING - - -/** - * @brief Get field time_last_baseline_ms from gps2_rtk message - * - * @return Time since boot of last baseline message received in ms. - */ -static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field rtk_receiver_id from gps2_rtk message - * - * @return Identification of connected RTK receiver. - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field wn from gps2_rtk message - * - * @return GPS Week Number of last baseline - */ -static inline uint16_t mavlink_msg_gps2_rtk_get_wn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field tow from gps2_rtk message - * - * @return GPS Time of Week of last baseline - */ -static inline uint32_t mavlink_msg_gps2_rtk_get_tow(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field rtk_health from gps2_rtk message - * - * @return GPS-specific health report for RTK data. - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field rtk_rate from gps2_rtk message - * - * @return Rate of baseline messages being received by GPS, in HZ - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field nsats from gps2_rtk message - * - * @return Current number of sats used for RTK calculation. - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field baseline_coords_type from gps2_rtk message - * - * @return Coordinate system of baseline. 0 == ECEF, 1 == NED - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field baseline_a_mm from gps2_rtk message - * - * @return Current baseline in ECEF x or NED north component in mm. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field baseline_b_mm from gps2_rtk message - * - * @return Current baseline in ECEF y or NED east component in mm. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field baseline_c_mm from gps2_rtk message - * - * @return Current baseline in ECEF z or NED down component in mm. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field accuracy from gps2_rtk message - * - * @return Current estimate of baseline accuracy. - */ -static inline uint32_t mavlink_msg_gps2_rtk_get_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field iar_num_hypotheses from gps2_rtk message - * - * @return Current number of integer ambiguity hypotheses. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 24); -} - -/** - * @brief Decode a gps2_rtk message into a struct - * - * @param msg The message to decode - * @param gps2_rtk C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps2_rtk_decode(const mavlink_message_t* msg, mavlink_gps2_rtk_t* gps2_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps2_rtk->time_last_baseline_ms = mavlink_msg_gps2_rtk_get_time_last_baseline_ms(msg); - gps2_rtk->tow = mavlink_msg_gps2_rtk_get_tow(msg); - gps2_rtk->baseline_a_mm = mavlink_msg_gps2_rtk_get_baseline_a_mm(msg); - gps2_rtk->baseline_b_mm = mavlink_msg_gps2_rtk_get_baseline_b_mm(msg); - gps2_rtk->baseline_c_mm = mavlink_msg_gps2_rtk_get_baseline_c_mm(msg); - gps2_rtk->accuracy = mavlink_msg_gps2_rtk_get_accuracy(msg); - gps2_rtk->iar_num_hypotheses = mavlink_msg_gps2_rtk_get_iar_num_hypotheses(msg); - gps2_rtk->wn = mavlink_msg_gps2_rtk_get_wn(msg); - gps2_rtk->rtk_receiver_id = mavlink_msg_gps2_rtk_get_rtk_receiver_id(msg); - gps2_rtk->rtk_health = mavlink_msg_gps2_rtk_get_rtk_health(msg); - gps2_rtk->rtk_rate = mavlink_msg_gps2_rtk_get_rtk_rate(msg); - gps2_rtk->nsats = mavlink_msg_gps2_rtk_get_nsats(msg); - gps2_rtk->baseline_coords_type = mavlink_msg_gps2_rtk_get_baseline_coords_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS2_RTK_LEN? msg->len : MAVLINK_MSG_ID_GPS2_RTK_LEN; - memset(gps2_rtk, 0, MAVLINK_MSG_ID_GPS2_RTK_LEN); - memcpy(gps2_rtk, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h b/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h deleted file mode 100644 index 3008058..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE GPS_GLOBAL_ORIGIN PACKING - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 - -MAVPACKED( -typedef struct __mavlink_gps_global_origin_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ -}) mavlink_gps_global_origin_t; - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN 12 -#define MAVLINK_MSG_ID_49_LEN 12 -#define MAVLINK_MSG_ID_49_MIN_LEN 12 - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39 -#define MAVLINK_MSG_ID_49_CRC 39 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ - 49, \ - "GPS_GLOBAL_ORIGIN", \ - 3, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ - "GPS_GLOBAL_ORIGIN", \ - 3, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_global_origin 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 latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (AMSL), 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[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, 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, 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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Pack a gps_global_origin message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (AMSL), 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, - mavlink_message_t* msg, - int32_t latitude,int32_t longitude,int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Encode a gps_global_origin struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) -{ - return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); -} - -/** - * @brief Encode a gps_global_origin struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) -{ - return mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, chan, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); -} - -/** - * @brief Send a gps_global_origin message - * @param chan MAVLink channel to send the message - * - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - */ -#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[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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -/** - * @brief Send a gps_global_origin message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_global_origin_send_struct(mavlink_channel_t chan, const mavlink_gps_global_origin_t* gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_global_origin_send(chan, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)gps_global_origin, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#else - mavlink_gps_global_origin_t *packet = (mavlink_gps_global_origin_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING - - -/** - * @brief Get field latitude from gps_global_origin message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from gps_global_origin message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from gps_global_origin message - * - * @return Altitude (AMSL), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Decode a gps_global_origin message into a struct - * - * @param msg The message to decode - * @param gps_global_origin C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_global_origin_t* gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_global_origin->latitude = mavlink_msg_gps_global_origin_get_latitude(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN? msg->len : MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN; - memset(gps_global_origin, 0, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); - memcpy(gps_global_origin, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h b/include/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h deleted file mode 100644 index 4fbd5fc..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE GPS_INJECT_DATA PACKING - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA 123 - -MAVPACKED( -typedef struct __mavlink_gps_inject_data_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t len; /*< data length*/ - uint8_t data[110]; /*< raw data (110 is enough for 12 satellites of RTCMv2)*/ -}) mavlink_gps_inject_data_t; - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113 -#define MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN 113 -#define MAVLINK_MSG_ID_123_LEN 113 -#define MAVLINK_MSG_ID_123_MIN_LEN 113 - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250 -#define MAVLINK_MSG_ID_123_CRC 250 - -#define MAVLINK_MSG_GPS_INJECT_DATA_FIELD_DATA_LEN 110 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \ - 123, \ - "GPS_INJECT_DATA", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \ - "GPS_INJECT_DATA", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_inject_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -} - -/** - * @brief Pack a gps_inject_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_inject_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t len,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -} - -/** - * @brief Encode a gps_inject_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_inject_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_inject_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) -{ - return mavlink_msg_gps_inject_data_pack(system_id, component_id, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); -} - -/** - * @brief Encode a gps_inject_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_inject_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_inject_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) -{ - return mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, chan, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); -} - -/** - * @brief Send a gps_inject_data message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_inject_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#endif -} - -/** - * @brief Send a gps_inject_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_inject_data_send_struct(mavlink_channel_t chan, const mavlink_gps_inject_data_t* gps_inject_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_inject_data_send(chan, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)gps_inject_data, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_inject_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - mavlink_gps_inject_data_t *packet = (mavlink_gps_inject_data_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_INJECT_DATA UNPACKING - - -/** - * @brief Get field target_system from gps_inject_data message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from gps_inject_data message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field len from gps_inject_data message - * - * @return data length - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field data from gps_inject_data message - * - * @return raw data (110 is enough for 12 satellites of RTCMv2) - */ -static inline uint16_t mavlink_msg_gps_inject_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 110, 3); -} - -/** - * @brief Decode a gps_inject_data message into a struct - * - * @param msg The message to decode - * @param gps_inject_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_inject_data_decode(const mavlink_message_t* msg, mavlink_gps_inject_data_t* gps_inject_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_inject_data->target_system = mavlink_msg_gps_inject_data_get_target_system(msg); - gps_inject_data->target_component = mavlink_msg_gps_inject_data_get_target_component(msg); - gps_inject_data->len = mavlink_msg_gps_inject_data_get_len(msg); - mavlink_msg_gps_inject_data_get_data(msg, gps_inject_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN? msg->len : MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN; - memset(gps_inject_data, 0, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); - memcpy(gps_inject_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_gps_input.h b/include/mavlink/v1.0/common/mavlink_msg_gps_input.h deleted file mode 100644 index 5fb9e9c..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_gps_input.h +++ /dev/null @@ -1,638 +0,0 @@ -#pragma once -// MESSAGE GPS_INPUT PACKING - -#define MAVLINK_MSG_ID_GPS_INPUT 232 - -MAVPACKED( -typedef struct __mavlink_gps_input_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - uint32_t time_week_ms; /*< GPS time (milliseconds from start of GPS week)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - float alt; /*< Altitude (AMSL, not WGS84), in m (positive for up)*/ - float hdop; /*< GPS HDOP horizontal dilution of position in m*/ - float vdop; /*< GPS VDOP vertical dilution of position in m*/ - float vn; /*< GPS velocity in m/s in NORTH direction in earth-fixed NED frame*/ - float ve; /*< GPS velocity in m/s in EAST direction in earth-fixed NED frame*/ - float vd; /*< GPS velocity in m/s in DOWN direction in earth-fixed NED frame*/ - float speed_accuracy; /*< GPS speed accuracy in m/s*/ - float horiz_accuracy; /*< GPS horizontal accuracy in m*/ - float vert_accuracy; /*< GPS vertical accuracy in m*/ - uint16_t ignore_flags; /*< Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided.*/ - uint16_t time_week; /*< GPS week number*/ - uint8_t gps_id; /*< ID of the GPS for multiple GPS inputs*/ - uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK*/ - uint8_t satellites_visible; /*< Number of satellites visible.*/ -}) mavlink_gps_input_t; - -#define MAVLINK_MSG_ID_GPS_INPUT_LEN 63 -#define MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN 63 -#define MAVLINK_MSG_ID_232_LEN 63 -#define MAVLINK_MSG_ID_232_MIN_LEN 63 - -#define MAVLINK_MSG_ID_GPS_INPUT_CRC 151 -#define MAVLINK_MSG_ID_232_CRC 151 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_INPUT { \ - 232, \ - "GPS_INPUT", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \ - { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \ - { "hdop", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_input_t, hdop) }, \ - { "vdop", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_input_t, vdop) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_input_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_input_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_input_t, vd) }, \ - { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \ - { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \ - { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \ - { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_INPUT { \ - "GPS_INPUT", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \ - { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \ - { "hdop", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_input_t, hdop) }, \ - { "vdop", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_input_t, vdop) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_input_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_input_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_input_t, vd) }, \ - { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \ - { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \ - { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \ - { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_input 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 (micros since boot or Unix epoch) - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - * @param time_week_ms GPS time (milliseconds from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in m (positive for up) - * @param hdop GPS HDOP horizontal dilution of position in m - * @param vdop GPS VDOP vertical dilution of position in m - * @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame - * @param speed_accuracy GPS speed accuracy in m/s - * @param horiz_accuracy GPS horizontal accuracy in m - * @param vert_accuracy GPS vertical accuracy in m - * @param satellites_visible Number of satellites visible. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#else - mavlink_gps_input_t packet; - packet.time_usec = time_usec; - packet.time_week_ms = time_week_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.hdop = hdop; - packet.vdop = vdop; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.speed_accuracy = speed_accuracy; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - packet.ignore_flags = ignore_flags; - packet.time_week = time_week; - packet.gps_id = gps_id; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INPUT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -} - -/** - * @brief Pack a gps_input message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - * @param time_week_ms GPS time (milliseconds from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in m (positive for up) - * @param hdop GPS HDOP horizontal dilution of position in m - * @param vdop GPS VDOP vertical dilution of position in m - * @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame - * @param speed_accuracy GPS speed accuracy in m/s - * @param horiz_accuracy GPS horizontal accuracy in m - * @param vert_accuracy GPS vertical accuracy in m - * @param satellites_visible Number of satellites visible. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_input_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t gps_id,uint16_t ignore_flags,uint32_t time_week_ms,uint16_t time_week,uint8_t fix_type,int32_t lat,int32_t lon,float alt,float hdop,float vdop,float vn,float ve,float vd,float speed_accuracy,float horiz_accuracy,float vert_accuracy,uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#else - mavlink_gps_input_t packet; - packet.time_usec = time_usec; - packet.time_week_ms = time_week_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.hdop = hdop; - packet.vdop = vdop; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.speed_accuracy = speed_accuracy; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - packet.ignore_flags = ignore_flags; - packet.time_week = time_week; - packet.gps_id = gps_id; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INPUT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -} - -/** - * @brief Encode a gps_input struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_input C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_input_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input) -{ - return mavlink_msg_gps_input_pack(system_id, component_id, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible); -} - -/** - * @brief Encode a gps_input struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_input C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_input_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input) -{ - return mavlink_msg_gps_input_pack_chan(system_id, component_id, chan, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible); -} - -/** - * @brief Send a gps_input message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - * @param time_week_ms GPS time (milliseconds from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in m (positive for up) - * @param hdop GPS HDOP horizontal dilution of position in m - * @param vdop GPS VDOP vertical dilution of position in m - * @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame - * @param speed_accuracy GPS speed accuracy in m/s - * @param horiz_accuracy GPS horizontal accuracy in m - * @param vert_accuracy GPS vertical accuracy in m - * @param satellites_visible Number of satellites visible. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_input_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#else - mavlink_gps_input_t packet; - packet.time_usec = time_usec; - packet.time_week_ms = time_week_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.hdop = hdop; - packet.vdop = vdop; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.speed_accuracy = speed_accuracy; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - packet.ignore_flags = ignore_flags; - packet.time_week = time_week; - packet.gps_id = gps_id; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)&packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#endif -} - -/** - * @brief Send a gps_input message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_input_send_struct(mavlink_channel_t chan, const mavlink_gps_input_t* gps_input) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_input_send(chan, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)gps_input, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_INPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_input_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#else - mavlink_gps_input_t *packet = (mavlink_gps_input_t *)msgbuf; - packet->time_usec = time_usec; - packet->time_week_ms = time_week_ms; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->hdop = hdop; - packet->vdop = vdop; - packet->vn = vn; - packet->ve = ve; - packet->vd = vd; - packet->speed_accuracy = speed_accuracy; - packet->horiz_accuracy = horiz_accuracy; - packet->vert_accuracy = vert_accuracy; - packet->ignore_flags = ignore_flags; - packet->time_week = time_week; - packet->gps_id = gps_id; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_INPUT UNPACKING - - -/** - * @brief Get field time_usec from gps_input message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_gps_input_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field gps_id from gps_input message - * - * @return ID of the GPS for multiple GPS inputs - */ -static inline uint8_t mavlink_msg_gps_input_get_gps_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 60); -} - -/** - * @brief Get field ignore_flags from gps_input message - * - * @return Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - */ -static inline uint16_t mavlink_msg_gps_input_get_ignore_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 56); -} - -/** - * @brief Get field time_week_ms from gps_input message - * - * @return GPS time (milliseconds from start of GPS week) - */ -static inline uint32_t mavlink_msg_gps_input_get_time_week_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field time_week from gps_input message - * - * @return GPS week number - */ -static inline uint16_t mavlink_msg_gps_input_get_time_week(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 58); -} - -/** - * @brief Get field fix_type from gps_input message - * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - */ -static inline uint8_t mavlink_msg_gps_input_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 61); -} - -/** - * @brief Get field lat from gps_input message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_input_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field lon from gps_input message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_input_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field alt from gps_input message - * - * @return Altitude (AMSL, not WGS84), in m (positive for up) - */ -static inline float mavlink_msg_gps_input_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field hdop from gps_input message - * - * @return GPS HDOP horizontal dilution of position in m - */ -static inline float mavlink_msg_gps_input_get_hdop(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vdop from gps_input message - * - * @return GPS VDOP vertical dilution of position in m - */ -static inline float mavlink_msg_gps_input_get_vdop(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field vn from gps_input message - * - * @return GPS velocity in m/s in NORTH direction in earth-fixed NED frame - */ -static inline float mavlink_msg_gps_input_get_vn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ve from gps_input message - * - * @return GPS velocity in m/s in EAST direction in earth-fixed NED frame - */ -static inline float mavlink_msg_gps_input_get_ve(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field vd from gps_input message - * - * @return GPS velocity in m/s in DOWN direction in earth-fixed NED frame - */ -static inline float mavlink_msg_gps_input_get_vd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field speed_accuracy from gps_input message - * - * @return GPS speed accuracy in m/s - */ -static inline float mavlink_msg_gps_input_get_speed_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field horiz_accuracy from gps_input message - * - * @return GPS horizontal accuracy in m - */ -static inline float mavlink_msg_gps_input_get_horiz_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field vert_accuracy from gps_input message - * - * @return GPS vertical accuracy in m - */ -static inline float mavlink_msg_gps_input_get_vert_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field satellites_visible from gps_input message - * - * @return Number of satellites visible. - */ -static inline uint8_t mavlink_msg_gps_input_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 62); -} - -/** - * @brief Decode a gps_input message into a struct - * - * @param msg The message to decode - * @param gps_input C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_input_decode(const mavlink_message_t* msg, mavlink_gps_input_t* gps_input) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_input->time_usec = mavlink_msg_gps_input_get_time_usec(msg); - gps_input->time_week_ms = mavlink_msg_gps_input_get_time_week_ms(msg); - gps_input->lat = mavlink_msg_gps_input_get_lat(msg); - gps_input->lon = mavlink_msg_gps_input_get_lon(msg); - gps_input->alt = mavlink_msg_gps_input_get_alt(msg); - gps_input->hdop = mavlink_msg_gps_input_get_hdop(msg); - gps_input->vdop = mavlink_msg_gps_input_get_vdop(msg); - gps_input->vn = mavlink_msg_gps_input_get_vn(msg); - gps_input->ve = mavlink_msg_gps_input_get_ve(msg); - gps_input->vd = mavlink_msg_gps_input_get_vd(msg); - gps_input->speed_accuracy = mavlink_msg_gps_input_get_speed_accuracy(msg); - gps_input->horiz_accuracy = mavlink_msg_gps_input_get_horiz_accuracy(msg); - gps_input->vert_accuracy = mavlink_msg_gps_input_get_vert_accuracy(msg); - gps_input->ignore_flags = mavlink_msg_gps_input_get_ignore_flags(msg); - gps_input->time_week = mavlink_msg_gps_input_get_time_week(msg); - gps_input->gps_id = mavlink_msg_gps_input_get_gps_id(msg); - gps_input->fix_type = mavlink_msg_gps_input_get_fix_type(msg); - gps_input->satellites_visible = mavlink_msg_gps_input_get_satellites_visible(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_INPUT_LEN? msg->len : MAVLINK_MSG_ID_GPS_INPUT_LEN; - memset(gps_input, 0, MAVLINK_MSG_ID_GPS_INPUT_LEN); - memcpy(gps_input, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h b/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h deleted file mode 100644 index 3033b6d..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE GPS_RAW_INT PACKING - -#define MAVLINK_MSG_ID_GPS_RAW_INT 24 - -MAVPACKED( -typedef struct __mavlink_gps_raw_int_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t alt; /*< Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/ - uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/ - uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ - uint8_t fix_type; /*< See the GPS_FIX_TYPE enum.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ -}) mavlink_gps_raw_int_t; - -#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 -#define MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN 30 -#define MAVLINK_MSG_ID_24_LEN 30 -#define MAVLINK_MSG_ID_24_MIN_LEN 30 - -#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24 -#define MAVLINK_MSG_ID_24_CRC 24 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ - 24, \ - "GPS_RAW_INT", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ - "GPS_RAW_INT", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_raw_int 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 since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - - 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; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - 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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -} - -/** - * @brief Pack a gps_raw_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - - 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; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - 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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -} - -/** - * @brief Encode a gps_raw_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_raw_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) -{ - return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); -} - -/** - * @brief Encode a gps_raw_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_raw_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) -{ - return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); -} - -/** - * @brief Send a gps_raw_int message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - mavlink_gps_raw_int_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - 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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#endif -} - -/** - * @brief Send a gps_raw_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_raw_int_send_struct(mavlink_channel_t chan, const mavlink_gps_raw_int_t* gps_raw_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_raw_int_send(chan, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)gps_raw_int, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - mavlink_gps_raw_int_t *packet = (mavlink_gps_raw_int_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->cog = cog; - 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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_RAW_INT UNPACKING - - -/** - * @brief Get field time_usec from gps_raw_int message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from gps_raw_int message - * - * @return See the GPS_FIX_TYPE enum. - */ -static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field lat from gps_raw_int message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from gps_raw_int message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from gps_raw_int message - * - * @return Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - */ -static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from gps_raw_int message - * - * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field epv from gps_raw_int message - * - * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field vel from gps_raw_int message - * - * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field cog from gps_raw_int message - * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field satellites_visible from gps_raw_int message - * - * @return Number of satellites visible. If unknown, set to 255 - */ -static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Decode a gps_raw_int message into a struct - * - * @param msg The message to decode - * @param gps_raw_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg); - gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg); - gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg); - gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg); - gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg); - gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg); - gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg); - gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(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 - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RAW_INT_LEN? msg->len : MAVLINK_MSG_ID_GPS_RAW_INT_LEN; - memset(gps_raw_int, 0, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); - memcpy(gps_raw_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_gps_rtcm_data.h b/include/mavlink/v1.0/common/mavlink_msg_gps_rtcm_data.h deleted file mode 100644 index 309a97b..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_gps_rtcm_data.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE GPS_RTCM_DATA PACKING - -#define MAVLINK_MSG_ID_GPS_RTCM_DATA 233 - -MAVPACKED( -typedef struct __mavlink_gps_rtcm_data_t { - uint8_t flags; /*< LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.*/ - uint8_t len; /*< data length*/ - uint8_t data[180]; /*< RTCM message (may be fragmented)*/ -}) mavlink_gps_rtcm_data_t; - -#define MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN 182 -#define MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN 182 -#define MAVLINK_MSG_ID_233_LEN 182 -#define MAVLINK_MSG_ID_233_MIN_LEN 182 - -#define MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC 35 -#define MAVLINK_MSG_ID_233_CRC 35 - -#define MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN 180 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA { \ - 233, \ - "GPS_RTCM_DATA", \ - 3, \ - { { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_rtcm_data_t, flags) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_rtcm_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 180, 2, offsetof(mavlink_gps_rtcm_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA { \ - "GPS_RTCM_DATA", \ - 3, \ - { { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_rtcm_data_t, flags) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_rtcm_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 180, 2, offsetof(mavlink_gps_rtcm_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_rtcm_data 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 flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - * @param len data length - * @param data RTCM message (may be fragmented) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t flags, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN]; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#else - mavlink_gps_rtcm_data_t packet; - packet.flags = flags; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTCM_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -} - -/** - * @brief Pack a gps_rtcm_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - * @param len data length - * @param data RTCM message (may be fragmented) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t flags,uint8_t len,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN]; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#else - mavlink_gps_rtcm_data_t packet; - packet.flags = flags; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTCM_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -} - -/** - * @brief Encode a gps_rtcm_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_rtcm_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ - return mavlink_msg_gps_rtcm_data_pack(system_id, component_id, msg, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data); -} - -/** - * @brief Encode a gps_rtcm_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_rtcm_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ - return mavlink_msg_gps_rtcm_data_pack_chan(system_id, component_id, chan, msg, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data); -} - -/** - * @brief Send a gps_rtcm_data message - * @param chan MAVLink channel to send the message - * - * @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - * @param len data length - * @param data RTCM message (may be fragmented) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_rtcm_data_send(mavlink_channel_t chan, uint8_t flags, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN]; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#else - mavlink_gps_rtcm_data_t packet; - packet.flags = flags; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#endif -} - -/** - * @brief Send a gps_rtcm_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_rtcm_data_send_struct(mavlink_channel_t chan, const mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_rtcm_data_send(chan, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (const char *)gps_rtcm_data, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_rtcm_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t flags, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#else - mavlink_gps_rtcm_data_t *packet = (mavlink_gps_rtcm_data_t *)msgbuf; - packet->flags = flags; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_RTCM_DATA UNPACKING - - -/** - * @brief Get field flags from gps_rtcm_data message - * - * @return LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - */ -static inline uint8_t mavlink_msg_gps_rtcm_data_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field len from gps_rtcm_data message - * - * @return data length - */ -static inline uint8_t mavlink_msg_gps_rtcm_data_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field data from gps_rtcm_data message - * - * @return RTCM message (may be fragmented) - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 180, 2); -} - -/** - * @brief Decode a gps_rtcm_data message into a struct - * - * @param msg The message to decode - * @param gps_rtcm_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_rtcm_data_decode(const mavlink_message_t* msg, mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_rtcm_data->flags = mavlink_msg_gps_rtcm_data_get_flags(msg); - gps_rtcm_data->len = mavlink_msg_gps_rtcm_data_get_len(msg); - mavlink_msg_gps_rtcm_data_get_data(msg, gps_rtcm_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN? msg->len : MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN; - memset(gps_rtcm_data, 0, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); - memcpy(gps_rtcm_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_gps_rtk.h b/include/mavlink/v1.0/common/mavlink_msg_gps_rtk.h deleted file mode 100644 index 3b25c80..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_gps_rtk.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE GPS_RTK PACKING - -#define MAVLINK_MSG_ID_GPS_RTK 127 - -MAVPACKED( -typedef struct __mavlink_gps_rtk_t { - uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/ - uint32_t tow; /*< GPS Time of Week of last baseline*/ - int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/ - int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/ - int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/ - uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ - int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ - uint16_t wn; /*< GPS Week Number of last baseline*/ - uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ - uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ - uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/ - uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ - uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/ -}) mavlink_gps_rtk_t; - -#define MAVLINK_MSG_ID_GPS_RTK_LEN 35 -#define MAVLINK_MSG_ID_GPS_RTK_MIN_LEN 35 -#define MAVLINK_MSG_ID_127_LEN 35 -#define MAVLINK_MSG_ID_127_MIN_LEN 35 - -#define MAVLINK_MSG_ID_GPS_RTK_CRC 25 -#define MAVLINK_MSG_ID_127_CRC 25 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_RTK { \ - 127, \ - "GPS_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_RTK { \ - "GPS_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_rtk 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_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); -#else - mavlink_gps_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -} - -/** - * @brief Pack a gps_rtk message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); -#else - mavlink_gps_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -} - -/** - * @brief Encode a gps_rtk struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) -{ - return mavlink_msg_gps_rtk_pack(system_id, component_id, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); -} - -/** - * @brief Encode a gps_rtk struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) -{ - return mavlink_msg_gps_rtk_pack_chan(system_id, component_id, chan, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); -} - -/** - * @brief Send a gps_rtk message - * @param chan MAVLink channel to send the message - * - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#else - mavlink_gps_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#endif -} - -/** - * @brief Send a gps_rtk message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_rtk_send_struct(mavlink_channel_t chan, const mavlink_gps_rtk_t* gps_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_rtk_send(chan, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)gps_rtk, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#else - mavlink_gps_rtk_t *packet = (mavlink_gps_rtk_t *)msgbuf; - packet->time_last_baseline_ms = time_last_baseline_ms; - packet->tow = tow; - packet->baseline_a_mm = baseline_a_mm; - packet->baseline_b_mm = baseline_b_mm; - packet->baseline_c_mm = baseline_c_mm; - packet->accuracy = accuracy; - packet->iar_num_hypotheses = iar_num_hypotheses; - packet->wn = wn; - packet->rtk_receiver_id = rtk_receiver_id; - packet->rtk_health = rtk_health; - packet->rtk_rate = rtk_rate; - packet->nsats = nsats; - packet->baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_RTK UNPACKING - - -/** - * @brief Get field time_last_baseline_ms from gps_rtk message - * - * @return Time since boot of last baseline message received in ms. - */ -static inline uint32_t mavlink_msg_gps_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field rtk_receiver_id from gps_rtk message - * - * @return Identification of connected RTK receiver. - */ -static inline uint8_t mavlink_msg_gps_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field wn from gps_rtk message - * - * @return GPS Week Number of last baseline - */ -static inline uint16_t mavlink_msg_gps_rtk_get_wn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field tow from gps_rtk message - * - * @return GPS Time of Week of last baseline - */ -static inline uint32_t mavlink_msg_gps_rtk_get_tow(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field rtk_health from gps_rtk message - * - * @return GPS-specific health report for RTK data. - */ -static inline uint8_t mavlink_msg_gps_rtk_get_rtk_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field rtk_rate from gps_rtk message - * - * @return Rate of baseline messages being received by GPS, in HZ - */ -static inline uint8_t mavlink_msg_gps_rtk_get_rtk_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field nsats from gps_rtk message - * - * @return Current number of sats used for RTK calculation. - */ -static inline uint8_t mavlink_msg_gps_rtk_get_nsats(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field baseline_coords_type from gps_rtk message - * - * @return Coordinate system of baseline. 0 == ECEF, 1 == NED - */ -static inline uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field baseline_a_mm from gps_rtk message - * - * @return Current baseline in ECEF x or NED north component in mm. - */ -static inline int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field baseline_b_mm from gps_rtk message - * - * @return Current baseline in ECEF y or NED east component in mm. - */ -static inline int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field baseline_c_mm from gps_rtk message - * - * @return Current baseline in ECEF z or NED down component in mm. - */ -static inline int32_t mavlink_msg_gps_rtk_get_baseline_c_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field accuracy from gps_rtk message - * - * @return Current estimate of baseline accuracy. - */ -static inline uint32_t mavlink_msg_gps_rtk_get_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field iar_num_hypotheses from gps_rtk message - * - * @return Current number of integer ambiguity hypotheses. - */ -static inline int32_t mavlink_msg_gps_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 24); -} - -/** - * @brief Decode a gps_rtk message into a struct - * - * @param msg The message to decode - * @param gps_rtk C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_rtk_decode(const mavlink_message_t* msg, mavlink_gps_rtk_t* gps_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_rtk->time_last_baseline_ms = mavlink_msg_gps_rtk_get_time_last_baseline_ms(msg); - gps_rtk->tow = mavlink_msg_gps_rtk_get_tow(msg); - gps_rtk->baseline_a_mm = mavlink_msg_gps_rtk_get_baseline_a_mm(msg); - gps_rtk->baseline_b_mm = mavlink_msg_gps_rtk_get_baseline_b_mm(msg); - gps_rtk->baseline_c_mm = mavlink_msg_gps_rtk_get_baseline_c_mm(msg); - gps_rtk->accuracy = mavlink_msg_gps_rtk_get_accuracy(msg); - gps_rtk->iar_num_hypotheses = mavlink_msg_gps_rtk_get_iar_num_hypotheses(msg); - gps_rtk->wn = mavlink_msg_gps_rtk_get_wn(msg); - gps_rtk->rtk_receiver_id = mavlink_msg_gps_rtk_get_rtk_receiver_id(msg); - gps_rtk->rtk_health = mavlink_msg_gps_rtk_get_rtk_health(msg); - gps_rtk->rtk_rate = mavlink_msg_gps_rtk_get_rtk_rate(msg); - gps_rtk->nsats = mavlink_msg_gps_rtk_get_nsats(msg); - gps_rtk->baseline_coords_type = mavlink_msg_gps_rtk_get_baseline_coords_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RTK_LEN? msg->len : MAVLINK_MSG_ID_GPS_RTK_LEN; - memset(gps_rtk, 0, MAVLINK_MSG_ID_GPS_RTK_LEN); - memcpy(gps_rtk, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_gps_status.h b/include/mavlink/v1.0/common/mavlink_msg_gps_status.h deleted file mode 100644 index 8511be9..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_gps_status.h +++ /dev/null @@ -1,334 +0,0 @@ -#pragma once -// MESSAGE GPS_STATUS PACKING - -#define MAVLINK_MSG_ID_GPS_STATUS 25 - -MAVPACKED( -typedef struct __mavlink_gps_status_t { - uint8_t satellites_visible; /*< Number of satellites visible*/ - uint8_t satellite_prn[20]; /*< Global satellite ID*/ - uint8_t satellite_used[20]; /*< 0: Satellite not used, 1: used for localization*/ - uint8_t satellite_elevation[20]; /*< Elevation (0: right on top of receiver, 90: on the horizon) of satellite*/ - uint8_t satellite_azimuth[20]; /*< Direction of satellite, 0: 0 deg, 255: 360 deg.*/ - uint8_t satellite_snr[20]; /*< Signal to noise ratio of satellite*/ -}) mavlink_gps_status_t; - -#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101 -#define MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN 101 -#define MAVLINK_MSG_ID_25_LEN 101 -#define MAVLINK_MSG_ID_25_MIN_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 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ - 25, \ - "GPS_STATUS", \ - 6, \ - { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ - { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ - { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ - { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ - { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ - { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ - "GPS_STATUS", \ - 6, \ - { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ - { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ - { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ - { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ - { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ - { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_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 satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - 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, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -} - -/** - * @brief Pack a gps_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - 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, 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, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -} - -/** - * @brief Encode a gps_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) -{ - return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); -} - -/** - * @brief Encode a gps_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) -{ - return mavlink_msg_gps_status_pack_chan(system_id, component_id, chan, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); -} - -/** - * @brief Send a gps_status message - * @param chan MAVLink channel to send the message - * - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - 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, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#endif -} - -/** - * @brief Send a gps_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_status_send_struct(mavlink_channel_t chan, const mavlink_gps_status_t* gps_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_status_send(chan, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)gps_status, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_status_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - mavlink_gps_status_t *packet = (mavlink_gps_status_t *)msgbuf; - packet->satellites_visible = satellites_visible; - mav_array_memcpy(packet->satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet->satellite_used, satellite_used, sizeof(uint8_t)*20); - 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, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_STATUS UNPACKING - - -/** - * @brief Get field satellites_visible from gps_status message - * - * @return Number of satellites visible - */ -static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field satellite_prn from gps_status message - * - * @return Global satellite ID - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1); -} - -/** - * @brief Get field satellite_used from gps_status message - * - * @return 0: Satellite not used, 1: used for localization - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21); -} - -/** - * @brief Get field satellite_elevation from gps_status message - * - * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41); -} - -/** - * @brief Get field satellite_azimuth from gps_status message - * - * @return Direction of satellite, 0: 0 deg, 255: 360 deg. - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61); -} - -/** - * @brief Get field satellite_snr from gps_status message - * - * @return Signal to noise ratio of satellite - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81); -} - -/** - * @brief Decode a gps_status message into a struct - * - * @param msg The message to decode - * @param gps_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg); - mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn); - mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used); - mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_GPS_STATUS_LEN; - memset(gps_status, 0, MAVLINK_MSG_ID_GPS_STATUS_LEN); - memcpy(gps_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h b/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h deleted file mode 100644 index 66020ff..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h +++ /dev/null @@ -1,335 +0,0 @@ -#pragma once -// MESSAGE HEARTBEAT PACKING - -#define MAVLINK_MSG_ID_HEARTBEAT 0 - -MAVPACKED( -typedef struct __mavlink_heartbeat_t { - uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/ - uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)*/ - uint8_t autopilot; /*< Autopilot type / class. defined in MAV_AUTOPILOT ENUM*/ - uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/ - uint8_t system_status; /*< System status flag, see MAV_STATE ENUM*/ - uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/ -}) mavlink_heartbeat_t; - -#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 -#define MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN 9 -#define MAVLINK_MSG_ID_0_LEN 9 -#define MAVLINK_MSG_ID_0_MIN_LEN 9 - -#define MAVLINK_MSG_ID_HEARTBEAT_CRC 50 -#define MAVLINK_MSG_ID_0_CRC 50 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ - 0, \ - "HEARTBEAT", \ - 6, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ - { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ - { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ - { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ - "HEARTBEAT", \ - 6, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ - { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ - { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ - { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ - } \ -} -#endif - -/** - * @brief Pack a heartbeat message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - - 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, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -} - -/** - * @brief Pack a heartbeat message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - - 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, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -} - -/** - * @brief Encode a heartbeat struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param heartbeat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) -{ - return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); -} - -/** - * @brief Encode a heartbeat struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param heartbeat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) -{ - return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); -} - -/** - * @brief Send a heartbeat message - * @param chan MAVLink channel to send the message - * - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_uint8_t(buf, 6, base_mode); - _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, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#endif -} - -/** - * @brief Send a heartbeat message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_heartbeat_send_struct(mavlink_channel_t chan, const mavlink_heartbeat_t* heartbeat) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_heartbeat_send(chan, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)heartbeat, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 5, autopilot); - _mav_put_uint8_t(buf, 6, base_mode); - _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, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf; - packet->custom_mode = custom_mode; - packet->type = type; - packet->autopilot = autopilot; - packet->base_mode = base_mode; - packet->system_status = system_status; - packet->mavlink_version = 3; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HEARTBEAT UNPACKING - - -/** - * @brief Get field type from heartbeat message - * - * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - */ -static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field autopilot from heartbeat message - * - * @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM - */ -static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field base_mode from heartbeat message - * - * @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - */ -static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field custom_mode from heartbeat message - * - * @return A bitfield for use for autopilot-specific flags. - */ -static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field system_status from heartbeat message - * - * @return System status flag, see MAV_STATE ENUM - */ -static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field mavlink_version from heartbeat message - * - * @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version - */ -static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Decode a heartbeat message into a struct - * - * @param msg The message to decode - * @param heartbeat C-struct to decode the message contents into - */ -static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg); - heartbeat->type = mavlink_msg_heartbeat_get_type(msg); - heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); - heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg); - heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg); - heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HEARTBEAT_LEN? msg->len : MAVLINK_MSG_ID_HEARTBEAT_LEN; - memset(heartbeat, 0, MAVLINK_MSG_ID_HEARTBEAT_LEN); - memcpy(heartbeat, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_high_latency.h b/include/mavlink/v1.0/common/mavlink_msg_high_latency.h deleted file mode 100644 index 7c87e5c..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_high_latency.h +++ /dev/null @@ -1,788 +0,0 @@ -#pragma once -// MESSAGE HIGH_LATENCY PACKING - -#define MAVLINK_MSG_ID_HIGH_LATENCY 234 - -MAVPACKED( -typedef struct __mavlink_high_latency_t { - uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/ - int32_t latitude; /*< Latitude, expressed as degrees * 1E7*/ - int32_t longitude; /*< Longitude, expressed as degrees * 1E7*/ - int16_t roll; /*< roll (centidegrees)*/ - int16_t pitch; /*< pitch (centidegrees)*/ - uint16_t heading; /*< heading (centidegrees)*/ - int16_t heading_sp; /*< heading setpoint (centidegrees)*/ - int16_t altitude_amsl; /*< Altitude above mean sea level (meters)*/ - int16_t altitude_sp; /*< Altitude setpoint relative to the home position (meters)*/ - uint16_t wp_distance; /*< distance to target (meters)*/ - uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/ - uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ - int8_t throttle; /*< throttle (percentage)*/ - uint8_t airspeed; /*< airspeed (m/s)*/ - uint8_t airspeed_sp; /*< airspeed setpoint (m/s)*/ - uint8_t groundspeed; /*< groundspeed (m/s)*/ - int8_t climb_rate; /*< climb rate (m/s)*/ - uint8_t gps_nsat; /*< Number of satellites visible. If unknown, set to 255*/ - uint8_t gps_fix_type; /*< See the GPS_FIX_TYPE enum.*/ - uint8_t battery_remaining; /*< Remaining battery (percentage)*/ - int8_t temperature; /*< Autopilot temperature (degrees C)*/ - int8_t temperature_air; /*< Air temperature (degrees C) from airspeed sensor*/ - uint8_t failsafe; /*< failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)*/ - uint8_t wp_num; /*< current waypoint number*/ -}) mavlink_high_latency_t; - -#define MAVLINK_MSG_ID_HIGH_LATENCY_LEN 40 -#define MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN 40 -#define MAVLINK_MSG_ID_234_LEN 40 -#define MAVLINK_MSG_ID_234_MIN_LEN 40 - -#define MAVLINK_MSG_ID_HIGH_LATENCY_CRC 150 -#define MAVLINK_MSG_ID_234_CRC 150 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY { \ - 234, \ - "HIGH_LATENCY", \ - 24, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \ - { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \ - { "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \ - { "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \ - { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \ - { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \ - { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \ - { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \ - { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 32, offsetof(mavlink_high_latency_t, climb_rate) }, \ - { "gps_nsat", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency_t, gps_nsat) }, \ - { "gps_fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency_t, gps_fix_type) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency_t, battery_remaining) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency_t, temperature) }, \ - { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \ - { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \ - { "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY { \ - "HIGH_LATENCY", \ - 24, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \ - { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \ - { "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \ - { "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \ - { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \ - { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \ - { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \ - { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \ - { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 32, offsetof(mavlink_high_latency_t, climb_rate) }, \ - { "gps_nsat", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency_t, gps_nsat) }, \ - { "gps_fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency_t, gps_fix_type) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency_t, battery_remaining) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency_t, temperature) }, \ - { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \ - { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \ - { "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \ - } \ -} -#endif - -/** - * @brief Pack a high_latency 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 base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll roll (centidegrees) - * @param pitch pitch (centidegrees) - * @param heading heading (centidegrees) - * @param throttle throttle (percentage) - * @param heading_sp heading setpoint (centidegrees) - * @param latitude Latitude, expressed as degrees * 1E7 - * @param longitude Longitude, expressed as degrees * 1E7 - * @param altitude_amsl Altitude above mean sea level (meters) - * @param altitude_sp Altitude setpoint relative to the home position (meters) - * @param airspeed airspeed (m/s) - * @param airspeed_sp airspeed setpoint (m/s) - * @param groundspeed groundspeed (m/s) - * @param climb_rate climb rate (m/s) - * @param gps_nsat Number of satellites visible. If unknown, set to 255 - * @param gps_fix_type See the GPS_FIX_TYPE enum. - * @param battery_remaining Remaining battery (percentage) - * @param temperature Autopilot temperature (degrees C) - * @param temperature_air Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance distance to target (meters) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_high_latency_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#else - mavlink_high_latency_t packet; - packet.custom_mode = custom_mode; - packet.latitude = latitude; - packet.longitude = longitude; - packet.roll = roll; - packet.pitch = pitch; - packet.heading = heading; - packet.heading_sp = heading_sp; - packet.altitude_amsl = altitude_amsl; - packet.altitude_sp = altitude_sp; - packet.wp_distance = wp_distance; - packet.base_mode = base_mode; - packet.landed_state = landed_state; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.climb_rate = climb_rate; - packet.gps_nsat = gps_nsat; - packet.gps_fix_type = gps_fix_type; - packet.battery_remaining = battery_remaining; - packet.temperature = temperature; - packet.temperature_air = temperature_air; - packet.failsafe = failsafe; - packet.wp_num = wp_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -} - -/** - * @brief Pack a high_latency message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll roll (centidegrees) - * @param pitch pitch (centidegrees) - * @param heading heading (centidegrees) - * @param throttle throttle (percentage) - * @param heading_sp heading setpoint (centidegrees) - * @param latitude Latitude, expressed as degrees * 1E7 - * @param longitude Longitude, expressed as degrees * 1E7 - * @param altitude_amsl Altitude above mean sea level (meters) - * @param altitude_sp Altitude setpoint relative to the home position (meters) - * @param airspeed airspeed (m/s) - * @param airspeed_sp airspeed setpoint (m/s) - * @param groundspeed groundspeed (m/s) - * @param climb_rate climb rate (m/s) - * @param gps_nsat Number of satellites visible. If unknown, set to 255 - * @param gps_fix_type See the GPS_FIX_TYPE enum. - * @param battery_remaining Remaining battery (percentage) - * @param temperature Autopilot temperature (degrees C) - * @param temperature_air Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance distance to target (meters) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_high_latency_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t base_mode,uint32_t custom_mode,uint8_t landed_state,int16_t roll,int16_t pitch,uint16_t heading,int8_t throttle,int16_t heading_sp,int32_t latitude,int32_t longitude,int16_t altitude_amsl,int16_t altitude_sp,uint8_t airspeed,uint8_t airspeed_sp,uint8_t groundspeed,int8_t climb_rate,uint8_t gps_nsat,uint8_t gps_fix_type,uint8_t battery_remaining,int8_t temperature,int8_t temperature_air,uint8_t failsafe,uint8_t wp_num,uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#else - mavlink_high_latency_t packet; - packet.custom_mode = custom_mode; - packet.latitude = latitude; - packet.longitude = longitude; - packet.roll = roll; - packet.pitch = pitch; - packet.heading = heading; - packet.heading_sp = heading_sp; - packet.altitude_amsl = altitude_amsl; - packet.altitude_sp = altitude_sp; - packet.wp_distance = wp_distance; - packet.base_mode = base_mode; - packet.landed_state = landed_state; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.climb_rate = climb_rate; - packet.gps_nsat = gps_nsat; - packet.gps_fix_type = gps_fix_type; - packet.battery_remaining = battery_remaining; - packet.temperature = temperature; - packet.temperature_air = temperature_air; - packet.failsafe = failsafe; - packet.wp_num = wp_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -} - -/** - * @brief Encode a high_latency struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param high_latency C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_high_latency_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_high_latency_t* high_latency) -{ - return mavlink_msg_high_latency_pack(system_id, component_id, msg, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance); -} - -/** - * @brief Encode a high_latency struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param high_latency C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_high_latency_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_high_latency_t* high_latency) -{ - return mavlink_msg_high_latency_pack_chan(system_id, component_id, chan, msg, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance); -} - -/** - * @brief Send a high_latency message - * @param chan MAVLink channel to send the message - * - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll roll (centidegrees) - * @param pitch pitch (centidegrees) - * @param heading heading (centidegrees) - * @param throttle throttle (percentage) - * @param heading_sp heading setpoint (centidegrees) - * @param latitude Latitude, expressed as degrees * 1E7 - * @param longitude Longitude, expressed as degrees * 1E7 - * @param altitude_amsl Altitude above mean sea level (meters) - * @param altitude_sp Altitude setpoint relative to the home position (meters) - * @param airspeed airspeed (m/s) - * @param airspeed_sp airspeed setpoint (m/s) - * @param groundspeed groundspeed (m/s) - * @param climb_rate climb rate (m/s) - * @param gps_nsat Number of satellites visible. If unknown, set to 255 - * @param gps_fix_type See the GPS_FIX_TYPE enum. - * @param battery_remaining Remaining battery (percentage) - * @param temperature Autopilot temperature (degrees C) - * @param temperature_air Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance distance to target (meters) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_high_latency_send(mavlink_channel_t chan, uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, buf, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#else - mavlink_high_latency_t packet; - packet.custom_mode = custom_mode; - packet.latitude = latitude; - packet.longitude = longitude; - packet.roll = roll; - packet.pitch = pitch; - packet.heading = heading; - packet.heading_sp = heading_sp; - packet.altitude_amsl = altitude_amsl; - packet.altitude_sp = altitude_sp; - packet.wp_distance = wp_distance; - packet.base_mode = base_mode; - packet.landed_state = landed_state; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.climb_rate = climb_rate; - packet.gps_nsat = gps_nsat; - packet.gps_fix_type = gps_fix_type; - packet.battery_remaining = battery_remaining; - packet.temperature = temperature; - packet.temperature_air = temperature_air; - packet.failsafe = failsafe; - packet.wp_num = wp_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)&packet, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#endif -} - -/** - * @brief Send a high_latency message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_high_latency_send_struct(mavlink_channel_t chan, const mavlink_high_latency_t* high_latency) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_high_latency_send(chan, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)high_latency, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIGH_LATENCY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_high_latency_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, buf, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#else - mavlink_high_latency_t *packet = (mavlink_high_latency_t *)msgbuf; - packet->custom_mode = custom_mode; - packet->latitude = latitude; - packet->longitude = longitude; - packet->roll = roll; - packet->pitch = pitch; - packet->heading = heading; - packet->heading_sp = heading_sp; - packet->altitude_amsl = altitude_amsl; - packet->altitude_sp = altitude_sp; - packet->wp_distance = wp_distance; - packet->base_mode = base_mode; - packet->landed_state = landed_state; - packet->throttle = throttle; - packet->airspeed = airspeed; - packet->airspeed_sp = airspeed_sp; - packet->groundspeed = groundspeed; - packet->climb_rate = climb_rate; - packet->gps_nsat = gps_nsat; - packet->gps_fix_type = gps_fix_type; - packet->battery_remaining = battery_remaining; - packet->temperature = temperature; - packet->temperature_air = temperature_air; - packet->failsafe = failsafe; - packet->wp_num = wp_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)packet, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIGH_LATENCY UNPACKING - - -/** - * @brief Get field base_mode from high_latency message - * - * @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - */ -static inline uint8_t mavlink_msg_high_latency_get_base_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field custom_mode from high_latency message - * - * @return A bitfield for use for autopilot-specific flags. - */ -static inline uint32_t mavlink_msg_high_latency_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field landed_state from high_latency message - * - * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - */ -static inline uint8_t mavlink_msg_high_latency_get_landed_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 27); -} - -/** - * @brief Get field roll from high_latency message - * - * @return roll (centidegrees) - */ -static inline int16_t mavlink_msg_high_latency_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field pitch from high_latency message - * - * @return pitch (centidegrees) - */ -static inline int16_t mavlink_msg_high_latency_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field heading from high_latency message - * - * @return heading (centidegrees) - */ -static inline uint16_t mavlink_msg_high_latency_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field throttle from high_latency message - * - * @return throttle (percentage) - */ -static inline int8_t mavlink_msg_high_latency_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 28); -} - -/** - * @brief Get field heading_sp from high_latency message - * - * @return heading setpoint (centidegrees) - */ -static inline int16_t mavlink_msg_high_latency_get_heading_sp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field latitude from high_latency message - * - * @return Latitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_high_latency_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field longitude from high_latency message - * - * @return Longitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_high_latency_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field altitude_amsl from high_latency message - * - * @return Altitude above mean sea level (meters) - */ -static inline int16_t mavlink_msg_high_latency_get_altitude_amsl(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field altitude_sp from high_latency message - * - * @return Altitude setpoint relative to the home position (meters) - */ -static inline int16_t mavlink_msg_high_latency_get_altitude_sp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field airspeed from high_latency message - * - * @return airspeed (m/s) - */ -static inline uint8_t mavlink_msg_high_latency_get_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field airspeed_sp from high_latency message - * - * @return airspeed setpoint (m/s) - */ -static inline uint8_t mavlink_msg_high_latency_get_airspeed_sp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field groundspeed from high_latency message - * - * @return groundspeed (m/s) - */ -static inline uint8_t mavlink_msg_high_latency_get_groundspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field climb_rate from high_latency message - * - * @return climb rate (m/s) - */ -static inline int8_t mavlink_msg_high_latency_get_climb_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 32); -} - -/** - * @brief Get field gps_nsat from high_latency message - * - * @return Number of satellites visible. If unknown, set to 255 - */ -static inline uint8_t mavlink_msg_high_latency_get_gps_nsat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field gps_fix_type from high_latency message - * - * @return See the GPS_FIX_TYPE enum. - */ -static inline uint8_t mavlink_msg_high_latency_get_gps_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field battery_remaining from high_latency message - * - * @return Remaining battery (percentage) - */ -static inline uint8_t mavlink_msg_high_latency_get_battery_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field temperature from high_latency message - * - * @return Autopilot temperature (degrees C) - */ -static inline int8_t mavlink_msg_high_latency_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 36); -} - -/** - * @brief Get field temperature_air from high_latency message - * - * @return Air temperature (degrees C) from airspeed sensor - */ -static inline int8_t mavlink_msg_high_latency_get_temperature_air(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 37); -} - -/** - * @brief Get field failsafe from high_latency message - * - * @return failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - */ -static inline uint8_t mavlink_msg_high_latency_get_failsafe(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 38); -} - -/** - * @brief Get field wp_num from high_latency message - * - * @return current waypoint number - */ -static inline uint8_t mavlink_msg_high_latency_get_wp_num(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 39); -} - -/** - * @brief Get field wp_distance from high_latency message - * - * @return distance to target (meters) - */ -static inline uint16_t mavlink_msg_high_latency_get_wp_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Decode a high_latency message into a struct - * - * @param msg The message to decode - * @param high_latency C-struct to decode the message contents into - */ -static inline void mavlink_msg_high_latency_decode(const mavlink_message_t* msg, mavlink_high_latency_t* high_latency) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - high_latency->custom_mode = mavlink_msg_high_latency_get_custom_mode(msg); - high_latency->latitude = mavlink_msg_high_latency_get_latitude(msg); - high_latency->longitude = mavlink_msg_high_latency_get_longitude(msg); - high_latency->roll = mavlink_msg_high_latency_get_roll(msg); - high_latency->pitch = mavlink_msg_high_latency_get_pitch(msg); - high_latency->heading = mavlink_msg_high_latency_get_heading(msg); - high_latency->heading_sp = mavlink_msg_high_latency_get_heading_sp(msg); - high_latency->altitude_amsl = mavlink_msg_high_latency_get_altitude_amsl(msg); - high_latency->altitude_sp = mavlink_msg_high_latency_get_altitude_sp(msg); - high_latency->wp_distance = mavlink_msg_high_latency_get_wp_distance(msg); - high_latency->base_mode = mavlink_msg_high_latency_get_base_mode(msg); - high_latency->landed_state = mavlink_msg_high_latency_get_landed_state(msg); - high_latency->throttle = mavlink_msg_high_latency_get_throttle(msg); - high_latency->airspeed = mavlink_msg_high_latency_get_airspeed(msg); - high_latency->airspeed_sp = mavlink_msg_high_latency_get_airspeed_sp(msg); - high_latency->groundspeed = mavlink_msg_high_latency_get_groundspeed(msg); - high_latency->climb_rate = mavlink_msg_high_latency_get_climb_rate(msg); - high_latency->gps_nsat = mavlink_msg_high_latency_get_gps_nsat(msg); - high_latency->gps_fix_type = mavlink_msg_high_latency_get_gps_fix_type(msg); - high_latency->battery_remaining = mavlink_msg_high_latency_get_battery_remaining(msg); - high_latency->temperature = mavlink_msg_high_latency_get_temperature(msg); - high_latency->temperature_air = mavlink_msg_high_latency_get_temperature_air(msg); - high_latency->failsafe = mavlink_msg_high_latency_get_failsafe(msg); - high_latency->wp_num = mavlink_msg_high_latency_get_wp_num(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIGH_LATENCY_LEN? msg->len : MAVLINK_MSG_ID_HIGH_LATENCY_LEN; - memset(high_latency, 0, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); - memcpy(high_latency, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h b/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h deleted file mode 100644 index be7e5d3..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h +++ /dev/null @@ -1,563 +0,0 @@ -#pragma once -// MESSAGE HIGHRES_IMU PACKING - -#define MAVLINK_MSG_ID_HIGHRES_IMU 105 - -MAVPACKED( -typedef struct __mavlink_highres_imu_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float xacc; /*< X acceleration (m/s^2)*/ - float yacc; /*< Y acceleration (m/s^2)*/ - float zacc; /*< Z acceleration (m/s^2)*/ - float xgyro; /*< Angular speed around X axis (rad / sec)*/ - float ygyro; /*< Angular speed around Y axis (rad / sec)*/ - float zgyro; /*< Angular speed around Z axis (rad / sec)*/ - float xmag; /*< X Magnetic field (Gauss)*/ - float ymag; /*< Y Magnetic field (Gauss)*/ - float zmag; /*< Z Magnetic field (Gauss)*/ - float abs_pressure; /*< Absolute pressure in millibar*/ - float diff_pressure; /*< Differential pressure in millibar*/ - float pressure_alt; /*< Altitude calculated from pressure*/ - float temperature; /*< Temperature in degrees celsius*/ - uint16_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature*/ -}) mavlink_highres_imu_t; - -#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62 -#define MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN 62 -#define MAVLINK_MSG_ID_105_LEN 62 -#define MAVLINK_MSG_ID_105_MIN_LEN 62 - -#define MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93 -#define MAVLINK_MSG_ID_105_CRC 93 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \ - 105, \ - "HIGHRES_IMU", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \ - "HIGHRES_IMU", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \ - } \ -} -#endif - -/** - * @brief Pack a highres_imu 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 xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - 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.temperature = temperature; - packet.fields_updated = fields_updated; - - 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, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -} - -/** - * @brief Pack a highres_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - 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.temperature = temperature; - packet.fields_updated = fields_updated; - - 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, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -} - -/** - * @brief Encode a highres_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param highres_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) -{ - return mavlink_msg_highres_imu_pack(system_id, component_id, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); -} - -/** - * @brief Encode a highres_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param highres_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) -{ - return mavlink_msg_highres_imu_pack_chan(system_id, component_id, chan, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); -} - -/** - * @brief Send a highres_imu message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _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, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - 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.temperature = temperature; - packet.fields_updated = fields_updated; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#endif -} - -/** - * @brief Send a highres_imu message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_highres_imu_send_struct(mavlink_channel_t chan, const mavlink_highres_imu_t* highres_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_highres_imu_send(chan, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)highres_imu, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIGHRES_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _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, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - mavlink_highres_imu_t *packet = (mavlink_highres_imu_t *)msgbuf; - packet->time_usec = time_usec; - 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->temperature = temperature; - packet->fields_updated = fields_updated; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIGHRES_IMU UNPACKING - - -/** - * @brief Get field time_usec from highres_imu message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field xacc from highres_imu message - * - * @return X acceleration (m/s^2) - */ -static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yacc from highres_imu message - * - * @return Y acceleration (m/s^2) - */ -static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field zacc from highres_imu message - * - * @return Z acceleration (m/s^2) - */ -static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field xgyro from highres_imu message - * - * @return Angular speed around X axis (rad / sec) - */ -static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field ygyro from highres_imu message - * - * @return Angular speed around Y axis (rad / sec) - */ -static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field zgyro from highres_imu message - * - * @return Angular speed around Z axis (rad / sec) - */ -static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field xmag from highres_imu message - * - * @return X Magnetic field (Gauss) - */ -static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ymag from highres_imu message - * - * @return Y Magnetic field (Gauss) - */ -static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field zmag from highres_imu message - * - * @return Z Magnetic field (Gauss) - */ -static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field abs_pressure from highres_imu message - * - * @return Absolute pressure in millibar - */ -static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field diff_pressure from highres_imu message - * - * @return Differential pressure in millibar - */ -static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field pressure_alt from highres_imu message - * - * @return Altitude calculated from pressure - */ -static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field temperature from highres_imu message - * - * @return Temperature in degrees celsius - */ -static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field fields_updated from highres_imu message - * - * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - */ -static inline uint16_t mavlink_msg_highres_imu_get_fields_updated(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 60); -} - -/** - * @brief Decode a highres_imu message into a struct - * - * @param msg The message to decode - * @param highres_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_highres_imu_decode(const mavlink_message_t* msg, mavlink_highres_imu_t* highres_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - highres_imu->time_usec = mavlink_msg_highres_imu_get_time_usec(msg); - highres_imu->xacc = mavlink_msg_highres_imu_get_xacc(msg); - highres_imu->yacc = mavlink_msg_highres_imu_get_yacc(msg); - highres_imu->zacc = mavlink_msg_highres_imu_get_zacc(msg); - highres_imu->xgyro = mavlink_msg_highres_imu_get_xgyro(msg); - highres_imu->ygyro = mavlink_msg_highres_imu_get_ygyro(msg); - highres_imu->zgyro = mavlink_msg_highres_imu_get_zgyro(msg); - highres_imu->xmag = mavlink_msg_highres_imu_get_xmag(msg); - highres_imu->ymag = mavlink_msg_highres_imu_get_ymag(msg); - highres_imu->zmag = mavlink_msg_highres_imu_get_zmag(msg); - highres_imu->abs_pressure = mavlink_msg_highres_imu_get_abs_pressure(msg); - highres_imu->diff_pressure = mavlink_msg_highres_imu_get_diff_pressure(msg); - highres_imu->pressure_alt = mavlink_msg_highres_imu_get_pressure_alt(msg); - highres_imu->temperature = mavlink_msg_highres_imu_get_temperature(msg); - highres_imu->fields_updated = mavlink_msg_highres_imu_get_fields_updated(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIGHRES_IMU_LEN? msg->len : MAVLINK_MSG_ID_HIGHRES_IMU_LEN; - memset(highres_imu, 0, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); - memcpy(highres_imu, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_hil_actuator_controls.h b/include/mavlink/v1.0/common/mavlink_msg_hil_actuator_controls.h deleted file mode 100644 index f60e920..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_hil_actuator_controls.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE HIL_ACTUATOR_CONTROLS PACKING - -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS 93 - -MAVPACKED( -typedef struct __mavlink_hil_actuator_controls_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - uint64_t flags; /*< Flags as bitfield, reserved for future use.*/ - float controls[16]; /*< Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.*/ - uint8_t mode; /*< System mode (MAV_MODE), includes arming state.*/ -}) mavlink_hil_actuator_controls_t; - -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN 81 -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN 81 -#define MAVLINK_MSG_ID_93_LEN 81 -#define MAVLINK_MSG_ID_93_MIN_LEN 81 - -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC 47 -#define MAVLINK_MSG_ID_93_CRC 47 - -#define MAVLINK_MSG_HIL_ACTUATOR_CONTROLS_FIELD_CONTROLS_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS { \ - 93, \ - "HIL_ACTUATOR_CONTROLS", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS { \ - "HIL_ACTUATOR_CONTROLS", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_actuator_controls 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 since UNIX epoch or microseconds since system boot) - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode (MAV_MODE), includes arming state. - * @param flags Flags as bitfield, reserved for future use. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#else - mavlink_hil_actuator_controls_t packet; - packet.time_usec = time_usec; - packet.flags = flags; - packet.mode = mode; - mav_array_memcpy(packet.controls, controls, sizeof(float)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -} - -/** - * @brief Pack a hil_actuator_controls message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode (MAV_MODE), includes arming state. - * @param flags Flags as bitfield, reserved for future use. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *controls,uint8_t mode,uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#else - mavlink_hil_actuator_controls_t packet; - packet.time_usec = time_usec; - packet.flags = flags; - packet.mode = mode; - mav_array_memcpy(packet.controls, controls, sizeof(float)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -} - -/** - * @brief Encode a hil_actuator_controls struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_actuator_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ - return mavlink_msg_hil_actuator_controls_pack(system_id, component_id, msg, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags); -} - -/** - * @brief Encode a hil_actuator_controls struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_actuator_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ - return mavlink_msg_hil_actuator_controls_pack_chan(system_id, component_id, chan, msg, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags); -} - -/** - * @brief Send a hil_actuator_controls message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode (MAV_MODE), includes arming state. - * @param flags Flags as bitfield, reserved for future use. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_actuator_controls_send(mavlink_channel_t chan, uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#else - mavlink_hil_actuator_controls_t packet; - packet.time_usec = time_usec; - packet.flags = flags; - packet.mode = mode; - mav_array_memcpy(packet.controls, controls, sizeof(float)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#endif -} - -/** - * @brief Send a hil_actuator_controls message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_actuator_controls_send_struct(mavlink_channel_t chan, const mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_actuator_controls_send(chan, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)hil_actuator_controls, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_actuator_controls_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#else - mavlink_hil_actuator_controls_t *packet = (mavlink_hil_actuator_controls_t *)msgbuf; - packet->time_usec = time_usec; - packet->flags = flags; - packet->mode = mode; - mav_array_memcpy(packet->controls, controls, sizeof(float)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_ACTUATOR_CONTROLS UNPACKING - - -/** - * @brief Get field time_usec from hil_actuator_controls message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_actuator_controls_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field controls from hil_actuator_controls message - * - * @return Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_get_controls(const mavlink_message_t* msg, float *controls) -{ - return _MAV_RETURN_float_array(msg, controls, 16, 16); -} - -/** - * @brief Get field mode from hil_actuator_controls message - * - * @return System mode (MAV_MODE), includes arming state. - */ -static inline uint8_t mavlink_msg_hil_actuator_controls_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 80); -} - -/** - * @brief Get field flags from hil_actuator_controls message - * - * @return Flags as bitfield, reserved for future use. - */ -static inline uint64_t mavlink_msg_hil_actuator_controls_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Decode a hil_actuator_controls message into a struct - * - * @param msg The message to decode - * @param hil_actuator_controls C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_actuator_controls_decode(const mavlink_message_t* msg, mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_actuator_controls->time_usec = mavlink_msg_hil_actuator_controls_get_time_usec(msg); - hil_actuator_controls->flags = mavlink_msg_hil_actuator_controls_get_flags(msg); - mavlink_msg_hil_actuator_controls_get_controls(msg, hil_actuator_controls->controls); - hil_actuator_controls->mode = mavlink_msg_hil_actuator_controls_get_mode(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN? msg->len : MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN; - memset(hil_actuator_controls, 0, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); - memcpy(hil_actuator_controls, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h b/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h deleted file mode 100644 index 39dca7e..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE HIL_CONTROLS PACKING - -#define MAVLINK_MSG_ID_HIL_CONTROLS 91 - -MAVPACKED( -typedef struct __mavlink_hil_controls_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - float roll_ailerons; /*< Control output -1 .. 1*/ - float pitch_elevator; /*< Control output -1 .. 1*/ - float yaw_rudder; /*< Control output -1 .. 1*/ - float throttle; /*< Throttle 0 .. 1*/ - float aux1; /*< Aux 1, -1 .. 1*/ - float aux2; /*< Aux 2, -1 .. 1*/ - float aux3; /*< Aux 3, -1 .. 1*/ - float aux4; /*< Aux 4, -1 .. 1*/ - uint8_t mode; /*< System mode (MAV_MODE)*/ - uint8_t nav_mode; /*< Navigation mode (MAV_NAV_MODE)*/ -}) mavlink_hil_controls_t; - -#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 -#define MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN 42 -#define MAVLINK_MSG_ID_91_LEN 42 -#define MAVLINK_MSG_ID_91_MIN_LEN 42 - -#define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63 -#define MAVLINK_MSG_ID_91_CRC 63 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ - 91, \ - "HIL_CONTROLS", \ - 11, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \ - { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ - { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ - { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ - { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ - { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \ - { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \ - { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \ - { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \ - { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ - "HIL_CONTROLS", \ - 11, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \ - { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ - { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ - { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ - { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ - { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \ - { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \ - { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \ - { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \ - { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_controls 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 since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - - 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, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -} - -/** - * @brief Pack a hil_controls message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - - 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, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -} - -/** - * @brief Encode a hil_controls struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) -{ - return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); -} - -/** - * @brief Encode a hil_controls struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) -{ - return mavlink_msg_hil_controls_pack_chan(system_id, component_id, chan, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); -} - -/** - * @brief Send a hil_controls message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _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, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#endif -} - -/** - * @brief Send a hil_controls message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_controls_send_struct(mavlink_channel_t chan, const mavlink_hil_controls_t* hil_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_controls_send(chan, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)hil_controls, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll_ailerons); - _mav_put_float(buf, 12, pitch_elevator); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _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, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - mavlink_hil_controls_t *packet = (mavlink_hil_controls_t *)msgbuf; - packet->time_usec = time_usec; - packet->roll_ailerons = roll_ailerons; - packet->pitch_elevator = pitch_elevator; - packet->yaw_rudder = yaw_rudder; - packet->throttle = throttle; - packet->aux1 = aux1; - packet->aux2 = aux2; - packet->aux3 = aux3; - packet->aux4 = aux4; - packet->mode = mode; - packet->nav_mode = nav_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_CONTROLS UNPACKING - - -/** - * @brief Get field time_usec from hil_controls message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field roll_ailerons from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pitch_elevator from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw_rudder from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field throttle from hil_controls message - * - * @return Throttle 0 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field aux1 from hil_controls message - * - * @return Aux 1, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field aux2 from hil_controls message - * - * @return Aux 2, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field aux3 from hil_controls message - * - * @return Aux 3, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field aux4 from hil_controls message - * - * @return Aux 4, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field mode from hil_controls message - * - * @return System mode (MAV_MODE) - */ -static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field nav_mode from hil_controls message - * - * @return Navigation mode (MAV_NAV_MODE) - */ -static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Decode a hil_controls message into a struct - * - * @param msg The message to decode - * @param hil_controls C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_controls->time_usec = mavlink_msg_hil_controls_get_time_usec(msg); - hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg); - hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg); - hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg); - hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg); - hil_controls->aux1 = mavlink_msg_hil_controls_get_aux1(msg); - hil_controls->aux2 = mavlink_msg_hil_controls_get_aux2(msg); - hil_controls->aux3 = mavlink_msg_hil_controls_get_aux3(msg); - hil_controls->aux4 = mavlink_msg_hil_controls_get_aux4(msg); - hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg); - hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_CONTROLS_LEN? msg->len : MAVLINK_MSG_ID_HIL_CONTROLS_LEN; - memset(hil_controls, 0, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); - memcpy(hil_controls, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h b/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h deleted file mode 100644 index 393006f..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE HIL_GPS PACKING - -#define MAVLINK_MSG_ID_HIL_GPS 113 - -MAVPACKED( -typedef struct __mavlink_hil_gps_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535*/ - uint16_t vel; /*< GPS ground speed in cm/s. If unknown, set to: 65535*/ - int16_t vn; /*< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame*/ - int16_t ve; /*< GPS velocity in cm/s in EAST direction in earth-fixed NED frame*/ - int16_t vd; /*< GPS velocity in cm/s in DOWN direction in earth-fixed NED frame*/ - uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535*/ - uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ -}) mavlink_hil_gps_t; - -#define MAVLINK_MSG_ID_HIL_GPS_LEN 36 -#define MAVLINK_MSG_ID_HIL_GPS_MIN_LEN 36 -#define MAVLINK_MSG_ID_113_LEN 36 -#define MAVLINK_MSG_ID_113_MIN_LEN 36 - -#define MAVLINK_MSG_ID_HIL_GPS_CRC 124 -#define MAVLINK_MSG_ID_113_CRC 124 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_GPS { \ - 113, \ - "HIL_GPS", \ - 13, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \ - { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_GPS { \ - "HIL_GPS", \ - 13, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \ - { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_gps 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 since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed in cm/s. If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_GPS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -} - -/** - * @brief Pack a hil_gps message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed in cm/s. If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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,int16_t vn,int16_t ve,int16_t vd,uint16_t cog,uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_GPS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -} - -/** - * @brief Encode a hil_gps struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_gps C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) -{ - return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); -} - -/** - * @brief Encode a hil_gps struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_gps C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) -{ - return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); -} - -/** - * @brief Send a hil_gps message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed in cm/s. If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#endif -} - -/** - * @brief Send a hil_gps message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_gps_send_struct(mavlink_channel_t chan, const mavlink_hil_gps_t* hil_gps) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_gps_send(chan, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)hil_gps, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, 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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->vn = vn; - packet->ve = ve; - packet->vd = vd; - packet->cog = cog; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_GPS UNPACKING - - -/** - * @brief Get field time_usec from hil_gps message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from hil_gps message - * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - */ -static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field lat from hil_gps message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from hil_gps message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from hil_gps message - * - * @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from hil_gps message - * - * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field epv from hil_gps message - * - * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field vel from hil_gps message - * - * @return GPS ground speed in cm/s. If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field vn from hil_gps message - * - * @return GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 26); -} - -/** - * @brief Get field ve from hil_gps message - * - * @return GPS velocity in cm/s in EAST direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 28); -} - -/** - * @brief Get field vd from hil_gps message - * - * @return GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 30); -} - -/** - * @brief Get field cog from hil_gps message - * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field satellites_visible from hil_gps message - * - * @return Number of satellites visible. If unknown, set to 255 - */ -static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Decode a hil_gps message into a struct - * - * @param msg The message to decode - * @param hil_gps C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavlink_hil_gps_t* hil_gps) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_gps->time_usec = mavlink_msg_hil_gps_get_time_usec(msg); - hil_gps->lat = mavlink_msg_hil_gps_get_lat(msg); - hil_gps->lon = mavlink_msg_hil_gps_get_lon(msg); - hil_gps->alt = mavlink_msg_hil_gps_get_alt(msg); - hil_gps->eph = mavlink_msg_hil_gps_get_eph(msg); - hil_gps->epv = mavlink_msg_hil_gps_get_epv(msg); - hil_gps->vel = mavlink_msg_hil_gps_get_vel(msg); - hil_gps->vn = mavlink_msg_hil_gps_get_vn(msg); - hil_gps->ve = mavlink_msg_hil_gps_get_ve(msg); - hil_gps->vd = mavlink_msg_hil_gps_get_vd(msg); - hil_gps->cog = mavlink_msg_hil_gps_get_cog(msg); - hil_gps->fix_type = mavlink_msg_hil_gps_get_fix_type(msg); - hil_gps->satellites_visible = mavlink_msg_hil_gps_get_satellites_visible(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_GPS_LEN? msg->len : MAVLINK_MSG_ID_HIL_GPS_LEN; - memset(hil_gps, 0, MAVLINK_MSG_ID_HIL_GPS_LEN); - memcpy(hil_gps, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h b/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h deleted file mode 100644 index 9d1cf8e..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h +++ /dev/null @@ -1,488 +0,0 @@ -#pragma once -// MESSAGE HIL_OPTICAL_FLOW PACKING - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114 - -MAVPACKED( -typedef struct __mavlink_hil_optical_flow_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ - float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ - float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ - float integrated_xgyro; /*< RH rotation around X axis (rad)*/ - float integrated_ygyro; /*< RH rotation around Y axis (rad)*/ - float integrated_zgyro; /*< RH rotation around Z axis (rad)*/ - uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/ - float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/ - int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ -}) mavlink_hil_optical_flow_t; - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44 -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN 44 -#define MAVLINK_MSG_ID_114_LEN 44 -#define MAVLINK_MSG_ID_114_MIN_LEN 44 - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 237 -#define MAVLINK_MSG_ID_114_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \ - 114, \ - "HIL_OPTICAL_FLOW", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \ - "HIL_OPTICAL_FLOW", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_optical_flow 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 sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -} - -/** - * @brief Pack a hil_optical_flow message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_id,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -} - -/** - * @brief Encode a hil_optical_flow struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) -{ - return mavlink_msg_hil_optical_flow_pack(system_id, component_id, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); -} - -/** - * @brief Encode a hil_optical_flow struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) -{ - return mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, chan, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); -} - -/** - * @brief Send a hil_optical_flow message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#endif -} - -/** - * @brief Send a hil_optical_flow message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_optical_flow_send_struct(mavlink_channel_t chan, const mavlink_hil_optical_flow_t* hil_optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_optical_flow_send(chan, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)hil_optical_flow, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - mavlink_hil_optical_flow_t *packet = (mavlink_hil_optical_flow_t *)msgbuf; - packet->time_usec = time_usec; - packet->integration_time_us = integration_time_us; - packet->integrated_x = integrated_x; - packet->integrated_y = integrated_y; - packet->integrated_xgyro = integrated_xgyro; - packet->integrated_ygyro = integrated_ygyro; - packet->integrated_zgyro = integrated_zgyro; - packet->time_delta_distance_us = time_delta_distance_us; - packet->distance = distance; - packet->temperature = temperature; - packet->sensor_id = sensor_id; - packet->quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_OPTICAL_FLOW UNPACKING - - -/** - * @brief Get field time_usec from hil_optical_flow message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from hil_optical_flow message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field integration_time_us from hil_optical_flow message - * - * @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - */ -static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field integrated_x from hil_optical_flow message - * - * @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field integrated_y from hil_optical_flow message - * - * @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field integrated_xgyro from hil_optical_flow message - * - * @return RH rotation around X axis (rad) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field integrated_ygyro from hil_optical_flow message - * - * @return RH rotation around Y axis (rad) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field integrated_zgyro from hil_optical_flow message - * - * @return RH rotation around Z axis (rad) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field temperature from hil_optical_flow message - * - * @return Temperature * 100 in centi-degrees Celsius - */ -static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 40); -} - -/** - * @brief Get field quality from hil_optical_flow message - * - * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - */ -static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 43); -} - -/** - * @brief Get field time_delta_distance_us from hil_optical_flow message - * - * @return Time in microseconds since the distance was sampled. - */ -static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 32); -} - -/** - * @brief Get field distance from hil_optical_flow message - * - * @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -static inline float mavlink_msg_hil_optical_flow_get_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a hil_optical_flow message into a struct - * - * @param msg The message to decode - * @param hil_optical_flow C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_optical_flow_decode(const mavlink_message_t* msg, mavlink_hil_optical_flow_t* hil_optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_optical_flow->time_usec = mavlink_msg_hil_optical_flow_get_time_usec(msg); - hil_optical_flow->integration_time_us = mavlink_msg_hil_optical_flow_get_integration_time_us(msg); - hil_optical_flow->integrated_x = mavlink_msg_hil_optical_flow_get_integrated_x(msg); - hil_optical_flow->integrated_y = mavlink_msg_hil_optical_flow_get_integrated_y(msg); - hil_optical_flow->integrated_xgyro = mavlink_msg_hil_optical_flow_get_integrated_xgyro(msg); - hil_optical_flow->integrated_ygyro = mavlink_msg_hil_optical_flow_get_integrated_ygyro(msg); - hil_optical_flow->integrated_zgyro = mavlink_msg_hil_optical_flow_get_integrated_zgyro(msg); - hil_optical_flow->time_delta_distance_us = mavlink_msg_hil_optical_flow_get_time_delta_distance_us(msg); - hil_optical_flow->distance = mavlink_msg_hil_optical_flow_get_distance(msg); - hil_optical_flow->temperature = mavlink_msg_hil_optical_flow_get_temperature(msg); - hil_optical_flow->sensor_id = mavlink_msg_hil_optical_flow_get_sensor_id(msg); - hil_optical_flow->quality = mavlink_msg_hil_optical_flow_get_quality(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN? msg->len : MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN; - memset(hil_optical_flow, 0, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); - memcpy(hil_optical_flow, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h b/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h deleted file mode 100644 index 04b8a45..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h +++ /dev/null @@ -1,538 +0,0 @@ -#pragma once -// MESSAGE HIL_RC_INPUTS_RAW PACKING - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92 - -MAVPACKED( -typedef struct __mavlink_hil_rc_inputs_raw_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds*/ - uint16_t chan9_raw; /*< RC channel 9 value, in microseconds*/ - uint16_t chan10_raw; /*< RC channel 10 value, in microseconds*/ - uint16_t chan11_raw; /*< RC channel 11 value, in microseconds*/ - uint16_t chan12_raw; /*< RC channel 12 value, in microseconds*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 255: 100%*/ -}) mavlink_hil_rc_inputs_raw_t; - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN 33 -#define MAVLINK_MSG_ID_92_LEN 33 -#define MAVLINK_MSG_ID_92_MIN_LEN 33 - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC 54 -#define MAVLINK_MSG_ID_92_CRC 54 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ - 92, \ - "HIL_RC_INPUTS_RAW", \ - 14, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ - "HIL_RC_INPUTS_RAW", \ - 14, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_rc_inputs_raw 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 since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - - 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; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -} - -/** - * @brief Pack a hil_rc_inputs_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - - 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; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -} - -/** - * @brief Encode a hil_rc_inputs_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_rc_inputs_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ - return mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); -} - -/** - * @brief Encode a hil_rc_inputs_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_rc_inputs_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ - return mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, chan, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); -} - -/** - * @brief Send a hil_rc_inputs_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - mavlink_hil_rc_inputs_raw_t packet; - packet.time_usec = time_usec; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#endif -} - -/** - * @brief Send a hil_rc_inputs_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_rc_inputs_raw_send_struct(mavlink_channel_t chan, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_rc_inputs_raw_send(chan, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)hil_rc_inputs_raw, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_rc_inputs_raw_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, chan1_raw); - _mav_put_uint16_t(buf, 10, chan2_raw); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - mavlink_hil_rc_inputs_raw_t *packet = (mavlink_hil_rc_inputs_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->chan9_raw = chan9_raw; - packet->chan10_raw = chan10_raw; - packet->chan11_raw = chan11_raw; - packet->chan12_raw = chan12_raw; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_RC_INPUTS_RAW UNPACKING - - -/** - * @brief Get field time_usec from hil_rc_inputs_raw message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field chan1_raw from hil_rc_inputs_raw message - * - * @return RC channel 1 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan2_raw from hil_rc_inputs_raw message - * - * @return RC channel 2 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan3_raw from hil_rc_inputs_raw message - * - * @return RC channel 3 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan4_raw from hil_rc_inputs_raw message - * - * @return RC channel 4 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan5_raw from hil_rc_inputs_raw message - * - * @return RC channel 5 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan6_raw from hil_rc_inputs_raw message - * - * @return RC channel 6 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field chan7_raw from hil_rc_inputs_raw message - * - * @return RC channel 7 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field chan8_raw from hil_rc_inputs_raw message - * - * @return RC channel 8 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field chan9_raw from hil_rc_inputs_raw message - * - * @return RC channel 9 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field chan10_raw from hil_rc_inputs_raw message - * - * @return RC channel 10 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field chan11_raw from hil_rc_inputs_raw message - * - * @return RC channel 11 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field chan12_raw from hil_rc_inputs_raw message - * - * @return RC channel 12 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field rssi from hil_rc_inputs_raw message - * - * @return Receive signal strength indicator, 0: 0%, 255: 100% - */ -static inline uint8_t mavlink_msg_hil_rc_inputs_raw_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Decode a hil_rc_inputs_raw message into a struct - * - * @param msg The message to decode - * @param hil_rc_inputs_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_rc_inputs_raw_decode(const mavlink_message_t* msg, mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_rc_inputs_raw->time_usec = mavlink_msg_hil_rc_inputs_raw_get_time_usec(msg); - hil_rc_inputs_raw->chan1_raw = mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(msg); - hil_rc_inputs_raw->chan2_raw = mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(msg); - hil_rc_inputs_raw->chan3_raw = mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(msg); - hil_rc_inputs_raw->chan4_raw = mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(msg); - hil_rc_inputs_raw->chan5_raw = mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(msg); - hil_rc_inputs_raw->chan6_raw = mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(msg); - hil_rc_inputs_raw->chan7_raw = mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(msg); - hil_rc_inputs_raw->chan8_raw = mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(msg); - hil_rc_inputs_raw->chan9_raw = mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(msg); - hil_rc_inputs_raw->chan10_raw = mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(msg); - hil_rc_inputs_raw->chan11_raw = mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN? msg->len : MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN; - memset(hil_rc_inputs_raw, 0, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); - memcpy(hil_rc_inputs_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h b/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h deleted file mode 100644 index e7f561d..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h +++ /dev/null @@ -1,563 +0,0 @@ -#pragma once -// MESSAGE HIL_SENSOR PACKING - -#define MAVLINK_MSG_ID_HIL_SENSOR 107 - -MAVPACKED( -typedef struct __mavlink_hil_sensor_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float xacc; /*< X acceleration (m/s^2)*/ - float yacc; /*< Y acceleration (m/s^2)*/ - float zacc; /*< Z acceleration (m/s^2)*/ - float xgyro; /*< Angular speed around X axis in body frame (rad / sec)*/ - float ygyro; /*< Angular speed around Y axis in body frame (rad / sec)*/ - float zgyro; /*< Angular speed around Z axis in body frame (rad / sec)*/ - float xmag; /*< X Magnetic field (Gauss)*/ - float ymag; /*< Y Magnetic field (Gauss)*/ - float zmag; /*< Z Magnetic field (Gauss)*/ - float abs_pressure; /*< Absolute pressure in millibar*/ - float diff_pressure; /*< Differential pressure (airspeed) in millibar*/ - float pressure_alt; /*< Altitude calculated from pressure*/ - float temperature; /*< Temperature in degrees celsius*/ - uint32_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.*/ -}) mavlink_hil_sensor_t; - -#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 64 -#define MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN 64 -#define MAVLINK_MSG_ID_107_LEN 64 -#define MAVLINK_MSG_ID_107_MIN_LEN 64 - -#define MAVLINK_MSG_ID_HIL_SENSOR_CRC 108 -#define MAVLINK_MSG_ID_107_CRC 108 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \ - 107, \ - "HIL_SENSOR", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_sensor_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_sensor_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_sensor_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_sensor_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_sensor_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_sensor_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_sensor_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_sensor_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_sensor_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hil_sensor_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hil_sensor_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hil_sensor_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hil_sensor_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hil_sensor_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT32_T, 0, 60, offsetof(mavlink_hil_sensor_t, fields_updated) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \ - "HIL_SENSOR", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_sensor_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_sensor_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_sensor_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_sensor_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_sensor_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_sensor_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_sensor_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_sensor_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_sensor_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hil_sensor_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hil_sensor_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hil_sensor_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hil_sensor_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hil_sensor_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT32_T, 0, 60, offsetof(mavlink_hil_sensor_t, fields_updated) }, \ - } \ -} -#endif - -/** - * @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 xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. - * @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 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, 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, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, 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.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.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; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -} - -/** - * @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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. - * @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 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,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, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, 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.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.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; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -} - -/** - * @brief Encode a hil_sensor struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param 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->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->temperature, hil_sensor->fields_updated); -} - -/** - * @brief Encode a hil_sensor struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor) -{ - return mavlink_msg_hil_sensor_pack_chan(system_id, component_id, chan, msg, hil_sensor->time_usec, 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->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 xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_sensor_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, 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, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - mavlink_hil_sensor_t packet; - packet.time_usec = time_usec; - 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.temperature = temperature; - packet.fields_updated = fields_updated; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#endif -} - -/** - * @brief Send a hil_sensor message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_sensor_send_struct(mavlink_channel_t chan, const mavlink_hil_sensor_t* hil_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_sensor_send(chan, hil_sensor->time_usec, 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->temperature, hil_sensor->fields_updated); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)hil_sensor, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, 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, uint32_t fields_updated) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - mavlink_hil_sensor_t *packet = (mavlink_hil_sensor_t *)msgbuf; - packet->time_usec = time_usec; - 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->temperature = temperature; - packet->fields_updated = fields_updated; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#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 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, 8); -} - -/** - * @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, 12); -} - -/** - * @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, 16); -} - -/** - * @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, 20); -} - -/** - * @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, 24); -} - -/** - * @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, 28); -} - -/** - * @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, 32); -} - -/** - * @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, 36); -} - -/** - * @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, 40); -} - -/** - * @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, 44); -} - -/** - * @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, 48); -} - -/** - * @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, 52); -} - -/** - * @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, 56); -} - -/** - * @brief Get field fields_updated from hil_sensor message - * - * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. - */ -static inline uint32_t mavlink_msg_hil_sensor_get_fields_updated(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 60); -} - -/** - * @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 || !MAVLINK_ALIGNED_FIELDS - hil_sensor->time_usec = mavlink_msg_hil_sensor_get_time_usec(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->temperature = mavlink_msg_hil_sensor_get_temperature(msg); - hil_sensor->fields_updated = mavlink_msg_hil_sensor_get_fields_updated(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_HIL_SENSOR_LEN; - memset(hil_sensor, 0, MAVLINK_MSG_ID_HIL_SENSOR_LEN); - memcpy(hil_sensor, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_hil_state.h b/include/mavlink/v1.0/common/mavlink_msg_hil_state.h deleted file mode 100644 index 722c583..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_hil_state.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE HIL_STATE PACKING - -#define MAVLINK_MSG_ID_HIL_STATE 90 - -MAVPACKED( -typedef struct __mavlink_hil_state_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - float roll; /*< Roll angle (rad)*/ - float pitch; /*< Pitch angle (rad)*/ - float yaw; /*< Yaw angle (rad)*/ - float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/ - float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/ - float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/ - int32_t lat; /*< Latitude, expressed as * 1E7*/ - int32_t lon; /*< Longitude, expressed as * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/ - int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/ - int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/ - int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ -}) mavlink_hil_state_t; - -#define MAVLINK_MSG_ID_HIL_STATE_LEN 56 -#define MAVLINK_MSG_ID_HIL_STATE_MIN_LEN 56 -#define MAVLINK_MSG_ID_90_LEN 56 -#define MAVLINK_MSG_ID_90_MIN_LEN 56 - -#define MAVLINK_MSG_ID_HIL_STATE_CRC 183 -#define MAVLINK_MSG_ID_90_CRC 183 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_STATE { \ - 90, \ - "HIL_STATE", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_STATE { \ - "HIL_STATE", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_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 time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - - 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, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -} - -/** - * @brief Pack a hil_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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - - 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, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -} - -/** - * @brief Encode a hil_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) -{ - return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); -} - -/** - * @brief Encode a hil_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) -{ - return mavlink_msg_hil_state_pack_chan(system_id, component_id, chan, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); -} - -/** - * @brief Send a hil_state message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _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, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#endif -} - -/** - * @brief Send a hil_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_state_send_struct(mavlink_channel_t chan, const mavlink_hil_state_t* hil_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_state_send(chan, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)hil_state, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _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, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - mavlink_hil_state_t *packet = (mavlink_hil_state_t *)msgbuf; - packet->time_usec = time_usec; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_STATE UNPACKING - - -/** - * @brief Get field time_usec from hil_state message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field roll from hil_state message - * - * @return Roll angle (rad) - */ -static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pitch from hil_state message - * - * @return Pitch angle (rad) - */ -static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw from hil_state message - * - * @return Yaw angle (rad) - */ -static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field rollspeed from hil_state message - * - * @return Body frame roll / phi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitchspeed from hil_state message - * - * @return Body frame pitch / theta angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yawspeed from hil_state message - * - * @return Body frame yaw / psi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field lat from hil_state message - * - * @return Latitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 32); -} - -/** - * @brief Get field lon from hil_state message - * - * @return Longitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 36); -} - -/** - * @brief Get field alt from hil_state message - * - * @return Altitude in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 40); -} - -/** - * @brief Get field vx from hil_state message - * - * @return Ground X Speed (Latitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 44); -} - -/** - * @brief Get field vy from hil_state message - * - * @return Ground Y Speed (Longitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 46); -} - -/** - * @brief Get field vz from hil_state message - * - * @return Ground Z Speed (Altitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 48); -} - -/** - * @brief Get field xacc from hil_state message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 50); -} - -/** - * @brief Get field yacc from hil_state message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 52); -} - -/** - * @brief Get field zacc from hil_state message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 54); -} - -/** - * @brief Decode a hil_state message into a struct - * - * @param msg The message to decode - * @param hil_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg); - hil_state->roll = mavlink_msg_hil_state_get_roll(msg); - hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg); - hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg); - hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg); - hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg); - hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg); - hil_state->lat = mavlink_msg_hil_state_get_lat(msg); - hil_state->lon = mavlink_msg_hil_state_get_lon(msg); - hil_state->alt = mavlink_msg_hil_state_get_alt(msg); - hil_state->vx = mavlink_msg_hil_state_get_vx(msg); - hil_state->vy = mavlink_msg_hil_state_get_vy(msg); - hil_state->vz = mavlink_msg_hil_state_get_vz(msg); - hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg); - hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg); - hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_STATE_LEN? msg->len : MAVLINK_MSG_ID_HIL_STATE_LEN; - memset(hil_state, 0, MAVLINK_MSG_ID_HIL_STATE_LEN); - memcpy(hil_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h b/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h deleted file mode 100644 index 3ad8071..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h +++ /dev/null @@ -1,580 +0,0 @@ -#pragma once -// MESSAGE HIL_STATE_QUATERNION PACKING - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115 - -MAVPACKED( -typedef struct __mavlink_hil_state_quaternion_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - float attitude_quaternion[4]; /*< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)*/ - float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/ - float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/ - float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/ - int32_t lat; /*< Latitude, expressed as * 1E7*/ - int32_t lon; /*< Longitude, expressed as * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/ - int16_t vx; /*< Ground X Speed (Latitude), expressed as cm/s*/ - int16_t vy; /*< Ground Y Speed (Longitude), expressed as cm/s*/ - int16_t vz; /*< Ground Z Speed (Altitude), expressed as cm/s*/ - uint16_t ind_airspeed; /*< Indicated airspeed, expressed as cm/s*/ - uint16_t true_airspeed; /*< True airspeed, expressed as cm/s*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ -}) mavlink_hil_state_quaternion_t; - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64 -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN 64 -#define MAVLINK_MSG_ID_115_LEN 64 -#define MAVLINK_MSG_ID_115_MIN_LEN 64 - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4 -#define MAVLINK_MSG_ID_115_CRC 4 - -#define MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_ATTITUDE_QUATERNION_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \ - 115, \ - "HIL_STATE_QUATERNION", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \ - { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \ - { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \ - { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \ - "HIL_STATE_QUATERNION", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \ - { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \ - { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \ - { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_state_quaternion 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 since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as cm/s - * @param vy Ground Y Speed (Longitude), expressed as cm/s - * @param vz Ground Z Speed (Altitude), expressed as cm/s - * @param ind_airspeed Indicated airspeed, expressed as cm/s - * @param true_airspeed True airspeed, expressed as cm/s - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -} - -/** - * @brief Pack a hil_state_quaternion message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as cm/s - * @param vy Ground Y Speed (Longitude), expressed as cm/s - * @param vz Ground Z Speed (Altitude), expressed as cm/s - * @param ind_airspeed Indicated airspeed, expressed as cm/s - * @param true_airspeed True airspeed, expressed as cm/s - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t ind_airspeed,uint16_t true_airspeed,int16_t xacc,int16_t yacc,int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -} - -/** - * @brief Encode a hil_state_quaternion struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_state_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ - return mavlink_msg_hil_state_quaternion_pack(system_id, component_id, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); -} - -/** - * @brief Encode a hil_state_quaternion struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_state_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ - return mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, chan, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); -} - -/** - * @brief Send a hil_state_quaternion message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as cm/s - * @param vy Ground Y Speed (Longitude), expressed as cm/s - * @param vz Ground Z Speed (Altitude), expressed as cm/s - * @param ind_airspeed Indicated airspeed, expressed as cm/s - * @param true_airspeed True airspeed, expressed as cm/s - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_state_quaternion_send(mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#endif -} - -/** - * @brief Send a hil_state_quaternion message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_state_quaternion_send_struct(mavlink_channel_t chan, const mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_state_quaternion_send(chan, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)hil_state_quaternion, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - mavlink_hil_state_quaternion_t *packet = (mavlink_hil_state_quaternion_t *)msgbuf; - packet->time_usec = time_usec; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->ind_airspeed = ind_airspeed; - packet->true_airspeed = true_airspeed; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - mav_array_memcpy(packet->attitude_quaternion, attitude_quaternion, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_STATE_QUATERNION UNPACKING - - -/** - * @brief Get field time_usec from hil_state_quaternion message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field attitude_quaternion from hil_state_quaternion message - * - * @return Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(const mavlink_message_t* msg, float *attitude_quaternion) -{ - return _MAV_RETURN_float_array(msg, attitude_quaternion, 4, 8); -} - -/** - * @brief Get field rollspeed from hil_state_quaternion message - * - * @return Body frame roll / phi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field pitchspeed from hil_state_quaternion message - * - * @return Body frame pitch / theta angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field yawspeed from hil_state_quaternion message - * - * @return Body frame yaw / psi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field lat from hil_state_quaternion message - * - * @return Latitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 36); -} - -/** - * @brief Get field lon from hil_state_quaternion message - * - * @return Longitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 40); -} - -/** - * @brief Get field alt from hil_state_quaternion message - * - * @return Altitude in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 44); -} - -/** - * @brief Get field vx from hil_state_quaternion message - * - * @return Ground X Speed (Latitude), expressed as cm/s - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 48); -} - -/** - * @brief Get field vy from hil_state_quaternion message - * - * @return Ground Y Speed (Longitude), expressed as cm/s - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 50); -} - -/** - * @brief Get field vz from hil_state_quaternion message - * - * @return Ground Z Speed (Altitude), expressed as cm/s - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 52); -} - -/** - * @brief Get field ind_airspeed from hil_state_quaternion message - * - * @return Indicated airspeed, expressed as cm/s - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 54); -} - -/** - * @brief Get field true_airspeed from hil_state_quaternion message - * - * @return True airspeed, expressed as cm/s - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 56); -} - -/** - * @brief Get field xacc from hil_state_quaternion message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 58); -} - -/** - * @brief Get field yacc from hil_state_quaternion message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 60); -} - -/** - * @brief Get field zacc from hil_state_quaternion message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 62); -} - -/** - * @brief Decode a hil_state_quaternion message into a struct - * - * @param msg The message to decode - * @param hil_state_quaternion C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_state_quaternion_decode(const mavlink_message_t* msg, mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_state_quaternion->time_usec = mavlink_msg_hil_state_quaternion_get_time_usec(msg); - mavlink_msg_hil_state_quaternion_get_attitude_quaternion(msg, hil_state_quaternion->attitude_quaternion); - hil_state_quaternion->rollspeed = mavlink_msg_hil_state_quaternion_get_rollspeed(msg); - hil_state_quaternion->pitchspeed = mavlink_msg_hil_state_quaternion_get_pitchspeed(msg); - hil_state_quaternion->yawspeed = mavlink_msg_hil_state_quaternion_get_yawspeed(msg); - hil_state_quaternion->lat = mavlink_msg_hil_state_quaternion_get_lat(msg); - hil_state_quaternion->lon = mavlink_msg_hil_state_quaternion_get_lon(msg); - hil_state_quaternion->alt = mavlink_msg_hil_state_quaternion_get_alt(msg); - hil_state_quaternion->vx = mavlink_msg_hil_state_quaternion_get_vx(msg); - hil_state_quaternion->vy = mavlink_msg_hil_state_quaternion_get_vy(msg); - hil_state_quaternion->vz = mavlink_msg_hil_state_quaternion_get_vz(msg); - hil_state_quaternion->ind_airspeed = mavlink_msg_hil_state_quaternion_get_ind_airspeed(msg); - hil_state_quaternion->true_airspeed = mavlink_msg_hil_state_quaternion_get_true_airspeed(msg); - hil_state_quaternion->xacc = mavlink_msg_hil_state_quaternion_get_xacc(msg); - hil_state_quaternion->yacc = mavlink_msg_hil_state_quaternion_get_yacc(msg); - hil_state_quaternion->zacc = mavlink_msg_hil_state_quaternion_get_zacc(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN? msg->len : MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN; - memset(hil_state_quaternion, 0, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); - memcpy(hil_state_quaternion, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_home_position.h b/include/mavlink/v1.0/common/mavlink_msg_home_position.h deleted file mode 100644 index d5ac5e5..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_home_position.h +++ /dev/null @@ -1,430 +0,0 @@ -#pragma once -// MESSAGE HOME_POSITION PACKING - -#define MAVLINK_MSG_ID_HOME_POSITION 242 - -MAVPACKED( -typedef struct __mavlink_home_position_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ - float x; /*< Local X position of this position in the local coordinate frame*/ - float y; /*< Local Y position of this position in the local coordinate frame*/ - float z; /*< Local Z position of this position in the local coordinate frame*/ - float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ - float approach_x; /*< Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_y; /*< Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_z; /*< Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ -}) mavlink_home_position_t; - -#define MAVLINK_MSG_ID_HOME_POSITION_LEN 52 -#define MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN 52 -#define MAVLINK_MSG_ID_242_LEN 52 -#define MAVLINK_MSG_ID_242_MIN_LEN 52 - -#define MAVLINK_MSG_ID_HOME_POSITION_CRC 104 -#define MAVLINK_MSG_ID_242_CRC 104 - -#define MAVLINK_MSG_HOME_POSITION_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HOME_POSITION { \ - 242, \ - "HOME_POSITION", \ - 10, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HOME_POSITION { \ - "HOME_POSITION", \ - 10, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \ - } \ -} -#endif - -/** - * @brief Pack a home_position 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 latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#else - mavlink_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HOME_POSITION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -} - -/** - * @brief Pack a home_position message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#else - mavlink_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HOME_POSITION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -} - -/** - * @brief Encode a home_position struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_home_position_t* home_position) -{ - return mavlink_msg_home_position_pack(system_id, component_id, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z); -} - -/** - * @brief Encode a home_position struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_home_position_t* home_position) -{ - return mavlink_msg_home_position_pack_chan(system_id, component_id, chan, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z); -} - -/** - * @brief Send a home_position message - * @param chan MAVLink channel to send the message - * - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#else - mavlink_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#endif -} - -/** - * @brief Send a home_position message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_home_position_send_struct(mavlink_channel_t chan, const mavlink_home_position_t* home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_home_position_send(chan, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)home_position, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#else - mavlink_home_position_t *packet = (mavlink_home_position_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->x = x; - packet->y = y; - packet->z = z; - packet->approach_x = approach_x; - packet->approach_y = approach_y; - packet->approach_z = approach_z; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HOME_POSITION UNPACKING - - -/** - * @brief Get field latitude from home_position message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from home_position message - * - * @return Longitude (WGS84, in degrees * 1E7 - */ -static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from home_position message - * - * @return Altitude (AMSL), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field x from home_position message - * - * @return Local X position of this position in the local coordinate frame - */ -static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field y from home_position message - * - * @return Local Y position of this position in the local coordinate frame - */ -static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field z from home_position message - * - * @return Local Z position of this position in the local coordinate frame - */ -static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field q from home_position message - * - * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - */ -static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 24); -} - -/** - * @brief Get field approach_x from home_position message - * - * @return Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_home_position_get_approach_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field approach_y from home_position message - * - * @return Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_home_position_get_approach_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field approach_z from home_position message - * - * @return Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_home_position_get_approach_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Decode a home_position message into a struct - * - * @param msg The message to decode - * @param home_position C-struct to decode the message contents into - */ -static inline void mavlink_msg_home_position_decode(const mavlink_message_t* msg, mavlink_home_position_t* home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - home_position->latitude = mavlink_msg_home_position_get_latitude(msg); - home_position->longitude = mavlink_msg_home_position_get_longitude(msg); - home_position->altitude = mavlink_msg_home_position_get_altitude(msg); - home_position->x = mavlink_msg_home_position_get_x(msg); - home_position->y = mavlink_msg_home_position_get_y(msg); - home_position->z = mavlink_msg_home_position_get_z(msg); - mavlink_msg_home_position_get_q(msg, home_position->q); - home_position->approach_x = mavlink_msg_home_position_get_approach_x(msg); - home_position->approach_y = mavlink_msg_home_position_get_approach_y(msg); - home_position->approach_z = mavlink_msg_home_position_get_approach_z(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HOME_POSITION_LEN? msg->len : MAVLINK_MSG_ID_HOME_POSITION_LEN; - memset(home_position, 0, MAVLINK_MSG_ID_HOME_POSITION_LEN); - memcpy(home_position, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_landing_target.h b/include/mavlink/v1.0/common/mavlink_msg_landing_target.h deleted file mode 100644 index c79dc66..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_landing_target.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE LANDING_TARGET PACKING - -#define MAVLINK_MSG_ID_LANDING_TARGET 149 - -MAVPACKED( -typedef struct __mavlink_landing_target_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float angle_x; /*< X-axis angular offset (in radians) of the target from the center of the image*/ - float angle_y; /*< Y-axis angular offset (in radians) of the target from the center of the image*/ - float distance; /*< Distance to the target from the vehicle in meters*/ - float size_x; /*< Size in radians of target along x-axis*/ - float size_y; /*< Size in radians of target along y-axis*/ - uint8_t target_num; /*< The ID of the target if multiple targets are present*/ - uint8_t frame; /*< MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.*/ -}) mavlink_landing_target_t; - -#define MAVLINK_MSG_ID_LANDING_TARGET_LEN 30 -#define MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN 30 -#define MAVLINK_MSG_ID_149_LEN 30 -#define MAVLINK_MSG_ID_149_MIN_LEN 30 - -#define MAVLINK_MSG_ID_LANDING_TARGET_CRC 200 -#define MAVLINK_MSG_ID_149_CRC 200 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \ - 149, \ - "LANDING_TARGET", \ - 8, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \ - { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \ - { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \ - { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \ - { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \ - { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \ - "LANDING_TARGET", \ - 8, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \ - { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \ - { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \ - { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \ - { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \ - { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a landing_target 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 (micros since boot or Unix epoch) - * @param target_num The ID of the target if multiple targets are present - * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - * @param angle_x X-axis angular offset (in radians) of the target from the center of the image - * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image - * @param distance Distance to the target from the vehicle in meters - * @param size_x Size in radians of target along x-axis - * @param size_y Size in radians of target along y-axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#else - mavlink_landing_target_t packet; - packet.time_usec = time_usec; - packet.angle_x = angle_x; - packet.angle_y = angle_y; - packet.distance = distance; - packet.size_x = size_x; - packet.size_y = size_y; - packet.target_num = target_num; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -} - -/** - * @brief Pack a landing_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param target_num The ID of the target if multiple targets are present - * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - * @param angle_x X-axis angular offset (in radians) of the target from the center of the image - * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image - * @param distance Distance to the target from the vehicle in meters - * @param size_x Size in radians of target along x-axis - * @param size_y Size in radians of target along y-axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t target_num,uint8_t frame,float angle_x,float angle_y,float distance,float size_x,float size_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#else - mavlink_landing_target_t packet; - packet.time_usec = time_usec; - packet.angle_x = angle_x; - packet.angle_y = angle_y; - packet.distance = distance; - packet.size_x = size_x; - packet.size_y = size_y; - packet.target_num = target_num; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -} - -/** - * @brief Encode a landing_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param landing_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_landing_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target) -{ - return mavlink_msg_landing_target_pack(system_id, component_id, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y); -} - -/** - * @brief Encode a landing_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param landing_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target) -{ - return mavlink_msg_landing_target_pack_chan(system_id, component_id, chan, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y); -} - -/** - * @brief Send a landing_target message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param target_num The ID of the target if multiple targets are present - * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - * @param angle_x X-axis angular offset (in radians) of the target from the center of the image - * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image - * @param distance Distance to the target from the vehicle in meters - * @param size_x Size in radians of target along x-axis - * @param size_y Size in radians of target along y-axis - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#else - mavlink_landing_target_t packet; - packet.time_usec = time_usec; - packet.angle_x = angle_x; - packet.angle_y = angle_y; - packet.distance = distance; - packet.size_x = size_x; - packet.size_y = size_y; - packet.target_num = target_num; - packet.frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#endif -} - -/** - * @brief Send a landing_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_landing_target_send_struct(mavlink_channel_t chan, const mavlink_landing_target_t* landing_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_landing_target_send(chan, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)landing_target, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LANDING_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#else - mavlink_landing_target_t *packet = (mavlink_landing_target_t *)msgbuf; - packet->time_usec = time_usec; - packet->angle_x = angle_x; - packet->angle_y = angle_y; - packet->distance = distance; - packet->size_x = size_x; - packet->size_y = size_y; - packet->target_num = target_num; - packet->frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LANDING_TARGET UNPACKING - - -/** - * @brief Get field time_usec from landing_target message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_landing_target_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field target_num from landing_target message - * - * @return The ID of the target if multiple targets are present - */ -static inline uint8_t mavlink_msg_landing_target_get_target_num(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field frame from landing_target message - * - * @return MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - */ -static inline uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field angle_x from landing_target message - * - * @return X-axis angular offset (in radians) of the target from the center of the image - */ -static inline float mavlink_msg_landing_target_get_angle_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field angle_y from landing_target message - * - * @return Y-axis angular offset (in radians) of the target from the center of the image - */ -static inline float mavlink_msg_landing_target_get_angle_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field distance from landing_target message - * - * @return Distance to the target from the vehicle in meters - */ -static inline float mavlink_msg_landing_target_get_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field size_x from landing_target message - * - * @return Size in radians of target along x-axis - */ -static inline float mavlink_msg_landing_target_get_size_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field size_y from landing_target message - * - * @return Size in radians of target along y-axis - */ -static inline float mavlink_msg_landing_target_get_size_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a landing_target message into a struct - * - * @param msg The message to decode - * @param landing_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_landing_target_decode(const mavlink_message_t* msg, mavlink_landing_target_t* landing_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - landing_target->time_usec = mavlink_msg_landing_target_get_time_usec(msg); - landing_target->angle_x = mavlink_msg_landing_target_get_angle_x(msg); - landing_target->angle_y = mavlink_msg_landing_target_get_angle_y(msg); - landing_target->distance = mavlink_msg_landing_target_get_distance(msg); - landing_target->size_x = mavlink_msg_landing_target_get_size_x(msg); - landing_target->size_y = mavlink_msg_landing_target_get_size_y(msg); - landing_target->target_num = mavlink_msg_landing_target_get_target_num(msg); - landing_target->frame = mavlink_msg_landing_target_get_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LANDING_TARGET_LEN? msg->len : MAVLINK_MSG_ID_LANDING_TARGET_LEN; - memset(landing_target, 0, MAVLINK_MSG_ID_LANDING_TARGET_LEN); - memcpy(landing_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h b/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h deleted file mode 100644 index 4634032..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE LOCAL_POSITION_NED PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 - -MAVPACKED( -typedef struct __mavlink_local_position_ned_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float x; /*< X Position*/ - float y; /*< Y Position*/ - float z; /*< Z Position*/ - float vx; /*< X Speed*/ - float vy; /*< Y Speed*/ - float vz; /*< Z Speed*/ -}) mavlink_local_position_ned_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN 28 -#define MAVLINK_MSG_ID_32_LEN 28 -#define MAVLINK_MSG_ID_32_MIN_LEN 28 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185 -#define MAVLINK_MSG_ID_32_CRC 185 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ - 32, \ - "LOCAL_POSITION_NED", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ - "LOCAL_POSITION_NED", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ - } \ -} -#endif - -/** - * @brief Pack a local_position_ned 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_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - - 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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -} - -/** - * @brief Pack a local_position_ned message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - - 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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -} - -/** - * @brief Encode a local_position_ned struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) -{ - return mavlink_msg_local_position_ned_pack(system_id, component_id, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); -} - -/** - * @brief Encode a local_position_ned struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) -{ - return mavlink_msg_local_position_ned_pack_chan(system_id, component_id, chan, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); -} - -/** - * @brief Send a local_position_ned message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - mavlink_local_position_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#endif -} - -/** - * @brief Send a local_position_ned message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_local_position_ned_send_struct(mavlink_channel_t chan, const mavlink_local_position_ned_t* local_position_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_local_position_ned_send(chan, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)local_position_ned, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - mavlink_local_position_ned_t *packet = (mavlink_local_position_ned_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_NED UNPACKING - - -/** - * @brief Get field time_boot_ms from local_position_ned message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field x from local_position_ned message - * - * @return X Position - */ -static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from local_position_ned message - * - * @return Y Position - */ -static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from local_position_ned message - * - * @return Z Position - */ -static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from local_position_ned message - * - * @return X Speed - */ -static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from local_position_ned message - * - * @return Y Speed - */ -static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from local_position_ned message - * - * @return Z Speed - */ -static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a local_position_ned message into a struct - * - * @param msg The message to decode - * @param local_position_ned C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_ned_decode(const mavlink_message_t* msg, mavlink_local_position_ned_t* local_position_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - local_position_ned->time_boot_ms = mavlink_msg_local_position_ned_get_time_boot_ms(msg); - local_position_ned->x = mavlink_msg_local_position_ned_get_x(msg); - local_position_ned->y = mavlink_msg_local_position_ned_get_y(msg); - local_position_ned->z = mavlink_msg_local_position_ned_get_z(msg); - local_position_ned->vx = mavlink_msg_local_position_ned_get_vx(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN; - memset(local_position_ned, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); - memcpy(local_position_ned, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_cov.h b/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_cov.h deleted file mode 100644 index e697e46..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_cov.h +++ /dev/null @@ -1,480 +0,0 @@ -#pragma once -// MESSAGE LOCAL_POSITION_NED_COV PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64 - -MAVPACKED( -typedef struct __mavlink_local_position_ned_cov_t { - uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/ - float x; /*< X Position*/ - float y; /*< Y Position*/ - float z; /*< Z Position*/ - float vx; /*< X Speed (m/s)*/ - float vy; /*< Y Speed (m/s)*/ - float vz; /*< Z Speed (m/s)*/ - float ax; /*< X Acceleration (m/s^2)*/ - float ay; /*< Y Acceleration (m/s^2)*/ - float az; /*< Z Acceleration (m/s^2)*/ - float covariance[45]; /*< Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)*/ - uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ -}) mavlink_local_position_ned_cov_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 225 -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN 225 -#define MAVLINK_MSG_ID_64_LEN 225 -#define MAVLINK_MSG_ID_64_MIN_LEN 225 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 191 -#define MAVLINK_MSG_ID_64_CRC 191 - -#define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 45 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \ - 64, \ - "LOCAL_POSITION_NED_COV", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vz) }, \ - { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, ax) }, \ - { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \ - { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \ - "LOCAL_POSITION_NED_COV", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vz) }, \ - { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, ax) }, \ - { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \ - { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a local_position_ned_cov 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 since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed (m/s) - * @param vy Y Speed (m/s) - * @param vz Z Speed (m/s) - * @param ax X Acceleration (m/s^2) - * @param ay Y Acceleration (m/s^2) - * @param az Z Acceleration (m/s^2) - * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_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_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#else - mavlink_local_position_ned_cov_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -} - -/** - * @brief Pack a local_position_ned_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed (m/s) - * @param vy Y Speed (m/s) - * @param vz Z Speed (m/s) - * @param ax X Acceleration (m/s^2) - * @param ay Y Acceleration (m/s^2) - * @param az Z Acceleration (m/s^2) - * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t estimator_type,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az,const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_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_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#else - mavlink_local_position_ned_cov_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -} - -/** - * @brief Encode a local_position_ned_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ - return mavlink_msg_local_position_ned_cov_pack(system_id, component_id, msg, local_position_ned_cov->time_usec, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); -} - -/** - * @brief Encode a local_position_ned_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ - return mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, chan, msg, local_position_ned_cov->time_usec, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); -} - -/** - * @brief Send a local_position_ned_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed (m/s) - * @param vy Y Speed (m/s) - * @param vz Z Speed (m/s) - * @param ax X Acceleration (m/s^2) - * @param ay Y Acceleration (m/s^2) - * @param az Z Acceleration (m/s^2) - * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_local_position_ned_cov_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_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_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#else - mavlink_local_position_ned_cov_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#endif -} - -/** - * @brief Send a local_position_ned_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_local_position_ned_cov_send_struct(mavlink_channel_t chan, const mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_local_position_ned_cov_send(chan, local_position_ned_cov->time_usec, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)local_position_ned_cov, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#else - mavlink_local_position_ned_cov_t *packet = (mavlink_local_position_ned_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->ax = ax; - packet->ay = ay; - packet->az = az; - packet->estimator_type = estimator_type; - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_NED_COV UNPACKING - - -/** - * @brief Get field time_usec from local_position_ned_cov message - * - * @return Timestamp (microseconds since system boot or since UNIX epoch) - */ -static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field estimator_type from local_position_ned_cov message - * - * @return Class id of the estimator this estimate originated from. - */ -static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 224); -} - -/** - * @brief Get field x from local_position_ned_cov message - * - * @return X Position - */ -static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from local_position_ned_cov message - * - * @return Y Position - */ -static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from local_position_ned_cov message - * - * @return Z Position - */ -static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vx from local_position_ned_cov message - * - * @return X Speed (m/s) - */ -static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vy from local_position_ned_cov message - * - * @return Y Speed (m/s) - */ -static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vz from local_position_ned_cov message - * - * @return Z Speed (m/s) - */ -static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field ax from local_position_ned_cov message - * - * @return X Acceleration (m/s^2) - */ -static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ay from local_position_ned_cov message - * - * @return Y Acceleration (m/s^2) - */ -static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field az from local_position_ned_cov message - * - * @return Z Acceleration (m/s^2) - */ -static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field covariance from local_position_ned_cov message - * - * @return Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 45, 44); -} - -/** - * @brief Decode a local_position_ned_cov message into a struct - * - * @param msg The message to decode - * @param local_position_ned_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_ned_cov_decode(const mavlink_message_t* msg, mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - local_position_ned_cov->time_usec = mavlink_msg_local_position_ned_cov_get_time_usec(msg); - local_position_ned_cov->x = mavlink_msg_local_position_ned_cov_get_x(msg); - local_position_ned_cov->y = mavlink_msg_local_position_ned_cov_get_y(msg); - local_position_ned_cov->z = mavlink_msg_local_position_ned_cov_get_z(msg); - local_position_ned_cov->vx = mavlink_msg_local_position_ned_cov_get_vx(msg); - local_position_ned_cov->vy = mavlink_msg_local_position_ned_cov_get_vy(msg); - local_position_ned_cov->vz = mavlink_msg_local_position_ned_cov_get_vz(msg); - local_position_ned_cov->ax = mavlink_msg_local_position_ned_cov_get_ax(msg); - local_position_ned_cov->ay = mavlink_msg_local_position_ned_cov_get_ay(msg); - local_position_ned_cov->az = mavlink_msg_local_position_ned_cov_get_az(msg); - mavlink_msg_local_position_ned_cov_get_covariance(msg, local_position_ned_cov->covariance); - local_position_ned_cov->estimator_type = mavlink_msg_local_position_ned_cov_get_estimator_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN; - memset(local_position_ned_cov, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); - memcpy(local_position_ned_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h b/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h deleted file mode 100644 index e87bcaa..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89 - -MAVPACKED( -typedef struct __mavlink_local_position_ned_system_global_offset_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float x; /*< X Position*/ - float y; /*< Y Position*/ - float z; /*< Z Position*/ - float roll; /*< Roll*/ - float pitch; /*< Pitch*/ - float yaw; /*< Yaw*/ -}) mavlink_local_position_ned_system_global_offset_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28 -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN 28 -#define MAVLINK_MSG_ID_89_LEN 28 -#define MAVLINK_MSG_ID_89_MIN_LEN 28 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231 -#define MAVLINK_MSG_ID_89_CRC 231 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \ - 89, \ - "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_system_global_offset_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_system_global_offset_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_system_global_offset_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_system_global_offset_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_system_global_offset_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_system_global_offset_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_system_global_offset_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \ - "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_system_global_offset_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_system_global_offset_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_system_global_offset_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_system_global_offset_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_system_global_offset_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_system_global_offset_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_system_global_offset_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a local_position_ned_system_global_offset 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_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -} - -/** - * @brief Pack a local_position_ned_system_global_offset message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -} - -/** - * @brief Encode a local_position_ned_system_global_offset struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_system_global_offset C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ - return mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); -} - -/** - * @brief Encode a local_position_ned_system_global_offset struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_system_global_offset C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ - return mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, chan, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); -} - -/** - * @brief Send a local_position_ned_system_global_offset message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - mavlink_local_position_ned_system_global_offset_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - _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_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#endif -} - -/** - * @brief Send a local_position_ned_system_global_offset message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_local_position_ned_system_global_offset_send_struct(mavlink_channel_t chan, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_local_position_ned_system_global_offset_send(chan, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)local_position_ned_system_global_offset, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_ned_system_global_offset_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - mavlink_local_position_ned_system_global_offset_t *packet = (mavlink_local_position_ned_system_global_offset_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - - _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_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET UNPACKING - - -/** - * @brief Get field time_boot_ms from local_position_ned_system_global_offset message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field x from local_position_ned_system_global_offset message - * - * @return X Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from local_position_ned_system_global_offset message - * - * @return Y Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from local_position_ned_system_global_offset message - * - * @return Z Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field roll from local_position_ned_system_global_offset message - * - * @return Roll - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitch from local_position_ned_system_global_offset message - * - * @return Pitch - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yaw from local_position_ned_system_global_offset message - * - * @return Yaw - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a local_position_ned_system_global_offset message into a struct - * - * @param msg The message to decode - * @param local_position_ned_system_global_offset C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_ned_system_global_offset_decode(const mavlink_message_t* msg, mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - local_position_ned_system_global_offset->time_boot_ms = mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(msg); - local_position_ned_system_global_offset->x = mavlink_msg_local_position_ned_system_global_offset_get_x(msg); - local_position_ned_system_global_offset->y = mavlink_msg_local_position_ned_system_global_offset_get_y(msg); - local_position_ned_system_global_offset->z = mavlink_msg_local_position_ned_system_global_offset_get_z(msg); - local_position_ned_system_global_offset->roll = mavlink_msg_local_position_ned_system_global_offset_get_roll(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN; - memset(local_position_ned_system_global_offset, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); - memcpy(local_position_ned_system_global_offset, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_log_data.h b/include/mavlink/v1.0/common/mavlink_msg_log_data.h deleted file mode 100644 index f4adf2f..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_log_data.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE LOG_DATA PACKING - -#define MAVLINK_MSG_ID_LOG_DATA 120 - -MAVPACKED( -typedef struct __mavlink_log_data_t { - uint32_t ofs; /*< Offset into the log*/ - uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ - uint8_t count; /*< Number of bytes (zero for end of log)*/ - uint8_t data[90]; /*< log data*/ -}) mavlink_log_data_t; - -#define MAVLINK_MSG_ID_LOG_DATA_LEN 97 -#define MAVLINK_MSG_ID_LOG_DATA_MIN_LEN 97 -#define MAVLINK_MSG_ID_120_LEN 97 -#define MAVLINK_MSG_ID_120_MIN_LEN 97 - -#define MAVLINK_MSG_ID_LOG_DATA_CRC 134 -#define MAVLINK_MSG_ID_120_CRC 134 - -#define MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN 90 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_DATA { \ - 120, \ - "LOG_DATA", \ - 4, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_DATA { \ - "LOG_DATA", \ - 4, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_data 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 id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -} - -/** - * @brief Pack a log_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t id,uint32_t ofs,uint8_t count,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -} - -/** - * @brief Encode a log_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_data_t* log_data) -{ - return mavlink_msg_log_data_pack(system_id, component_id, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); -} - -/** - * @brief Encode a log_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_data_t* log_data) -{ - return mavlink_msg_log_data_pack_chan(system_id, component_id, chan, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); -} - -/** - * @brief Send a log_data message - * @param chan MAVLink channel to send the message - * - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_data_send(mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#endif -} - -/** - * @brief Send a log_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_data_send_struct(mavlink_channel_t chan, const mavlink_log_data_t* log_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_data_send(chan, log_data->id, log_data->ofs, log_data->count, log_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)log_data, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - mavlink_log_data_t *packet = (mavlink_log_data_t *)msgbuf; - packet->ofs = ofs; - packet->id = id; - packet->count = count; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_DATA UNPACKING - - -/** - * @brief Get field id from log_data message - * - * @return Log id (from LOG_ENTRY reply) - */ -static inline uint16_t mavlink_msg_log_data_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field ofs from log_data message - * - * @return Offset into the log - */ -static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from log_data message - * - * @return Number of bytes (zero for end of log) - */ -static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field data from log_data message - * - * @return log data - */ -static inline uint16_t mavlink_msg_log_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 90, 7); -} - -/** - * @brief Decode a log_data message into a struct - * - * @param msg The message to decode - * @param log_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_data_decode(const mavlink_message_t* msg, mavlink_log_data_t* log_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_data->ofs = mavlink_msg_log_data_get_ofs(msg); - log_data->id = mavlink_msg_log_data_get_id(msg); - log_data->count = mavlink_msg_log_data_get_count(msg); - mavlink_msg_log_data_get_data(msg, log_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_DATA_LEN? msg->len : MAVLINK_MSG_ID_LOG_DATA_LEN; - memset(log_data, 0, MAVLINK_MSG_ID_LOG_DATA_LEN); - memcpy(log_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_log_entry.h b/include/mavlink/v1.0/common/mavlink_msg_log_entry.h deleted file mode 100644 index 733e4e7..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_log_entry.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE LOG_ENTRY PACKING - -#define MAVLINK_MSG_ID_LOG_ENTRY 118 - -MAVPACKED( -typedef struct __mavlink_log_entry_t { - uint32_t time_utc; /*< UTC timestamp of log in seconds since 1970, or 0 if not available*/ - uint32_t size; /*< Size of the log (may be approximate) in bytes*/ - uint16_t id; /*< Log id*/ - uint16_t num_logs; /*< Total number of logs*/ - uint16_t last_log_num; /*< High log number*/ -}) mavlink_log_entry_t; - -#define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 -#define MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN 14 -#define MAVLINK_MSG_ID_118_LEN 14 -#define MAVLINK_MSG_ID_118_MIN_LEN 14 - -#define MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 -#define MAVLINK_MSG_ID_118_CRC 56 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ - 118, \ - "LOG_ENTRY", \ - 5, \ - { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ - { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ - { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ - "LOG_ENTRY", \ - 5, \ - { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ - { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ - { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_entry 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 id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -} - -/** - * @brief Pack a log_entry message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_entry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t id,uint16_t num_logs,uint16_t last_log_num,uint32_t time_utc,uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -} - -/** - * @brief Encode a log_entry struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_entry C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_entry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) -{ - return mavlink_msg_log_entry_pack(system_id, component_id, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); -} - -/** - * @brief Encode a log_entry struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_entry C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_entry_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) -{ - return mavlink_msg_log_entry_pack_chan(system_id, component_id, chan, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); -} - -/** - * @brief Send a log_entry message - * @param chan MAVLink channel to send the message - * - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_entry_send(mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#endif -} - -/** - * @brief Send a log_entry message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_entry_send_struct(mavlink_channel_t chan, const mavlink_log_entry_t* log_entry) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_entry_send(chan, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)log_entry, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_ENTRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_entry_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - mavlink_log_entry_t *packet = (mavlink_log_entry_t *)msgbuf; - packet->time_utc = time_utc; - packet->size = size; - packet->id = id; - packet->num_logs = num_logs; - packet->last_log_num = last_log_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_ENTRY UNPACKING - - -/** - * @brief Get field id from log_entry message - * - * @return Log id - */ -static inline uint16_t mavlink_msg_log_entry_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field num_logs from log_entry message - * - * @return Total number of logs - */ -static inline uint16_t mavlink_msg_log_entry_get_num_logs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field last_log_num from log_entry message - * - * @return High log number - */ -static inline uint16_t mavlink_msg_log_entry_get_last_log_num(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field time_utc from log_entry message - * - * @return UTC timestamp of log in seconds since 1970, or 0 if not available - */ -static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field size from log_entry message - * - * @return Size of the log (may be approximate) in bytes - */ -static inline uint32_t mavlink_msg_log_entry_get_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Decode a log_entry message into a struct - * - * @param msg The message to decode - * @param log_entry C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_entry_decode(const mavlink_message_t* msg, mavlink_log_entry_t* log_entry) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_entry->time_utc = mavlink_msg_log_entry_get_time_utc(msg); - log_entry->size = mavlink_msg_log_entry_get_size(msg); - log_entry->id = mavlink_msg_log_entry_get_id(msg); - log_entry->num_logs = mavlink_msg_log_entry_get_num_logs(msg); - log_entry->last_log_num = mavlink_msg_log_entry_get_last_log_num(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_ENTRY_LEN? msg->len : MAVLINK_MSG_ID_LOG_ENTRY_LEN; - memset(log_entry, 0, MAVLINK_MSG_ID_LOG_ENTRY_LEN); - memcpy(log_entry, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_log_erase.h b/include/mavlink/v1.0/common/mavlink_msg_log_erase.h deleted file mode 100644 index d603771..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_log_erase.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE LOG_ERASE PACKING - -#define MAVLINK_MSG_ID_LOG_ERASE 121 - -MAVPACKED( -typedef struct __mavlink_log_erase_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_erase_t; - -#define MAVLINK_MSG_ID_LOG_ERASE_LEN 2 -#define MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN 2 -#define MAVLINK_MSG_ID_121_LEN 2 -#define MAVLINK_MSG_ID_121_MIN_LEN 2 - -#define MAVLINK_MSG_ID_LOG_ERASE_CRC 237 -#define MAVLINK_MSG_ID_121_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_ERASE { \ - 121, \ - "LOG_ERASE", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_erase_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_erase_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_ERASE { \ - "LOG_ERASE", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_erase_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_erase_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_erase message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_erase_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -} - -/** - * @brief Pack a log_erase message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_erase_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -} - -/** - * @brief Encode a log_erase struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_erase C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_erase_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) -{ - return mavlink_msg_log_erase_pack(system_id, component_id, msg, log_erase->target_system, log_erase->target_component); -} - -/** - * @brief Encode a log_erase struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_erase C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_erase_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) -{ - return mavlink_msg_log_erase_pack_chan(system_id, component_id, chan, msg, log_erase->target_system, log_erase->target_component); -} - -/** - * @brief Send a log_erase message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_erase_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_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_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#endif -} - -/** - * @brief Send a log_erase message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_erase_send_struct(mavlink_channel_t chan, const mavlink_log_erase_t* log_erase) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_erase_send(chan, log_erase->target_system, log_erase->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)log_erase, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_ERASE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_erase_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - mavlink_log_erase_t *packet = (mavlink_log_erase_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_ERASE UNPACKING - - -/** - * @brief Get field target_system from log_erase message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_erase_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from log_erase message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_erase_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a log_erase message into a struct - * - * @param msg The message to decode - * @param log_erase C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_erase_decode(const mavlink_message_t* msg, mavlink_log_erase_t* log_erase) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_erase->target_system = mavlink_msg_log_erase_get_target_system(msg); - log_erase->target_component = mavlink_msg_log_erase_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_ERASE_LEN? msg->len : MAVLINK_MSG_ID_LOG_ERASE_LEN; - memset(log_erase, 0, MAVLINK_MSG_ID_LOG_ERASE_LEN); - memcpy(log_erase, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h b/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h deleted file mode 100644 index 3fb3d62..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE LOG_REQUEST_DATA PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119 - -MAVPACKED( -typedef struct __mavlink_log_request_data_t { - uint32_t ofs; /*< Offset into the log*/ - uint32_t count; /*< Number of bytes*/ - uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_request_data_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12 -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN 12 -#define MAVLINK_MSG_ID_119_LEN 12 -#define MAVLINK_MSG_ID_119_MIN_LEN 12 - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116 -#define MAVLINK_MSG_ID_119_CRC 116 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \ - 119, \ - "LOG_REQUEST_DATA", \ - 5, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ - { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \ - "LOG_REQUEST_DATA", \ - 5, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ - { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_request_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -} - -/** - * @brief Pack a log_request_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t id,uint32_t ofs,uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -} - -/** - * @brief Encode a log_request_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) -{ - return mavlink_msg_log_request_data_pack(system_id, component_id, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); -} - -/** - * @brief Encode a log_request_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) -{ - return mavlink_msg_log_request_data_pack_chan(system_id, component_id, chan, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); -} - -/** - * @brief Send a log_request_data message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#endif -} - -/** - * @brief Send a log_request_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_request_data_send_struct(mavlink_channel_t chan, const mavlink_log_request_data_t* log_request_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_request_data_send(chan, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)log_request_data, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - mavlink_log_request_data_t *packet = (mavlink_log_request_data_t *)msgbuf; - packet->ofs = ofs; - packet->count = count; - packet->id = id; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_DATA UNPACKING - - -/** - * @brief Get field target_system from log_request_data message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_data_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field target_component from log_request_data message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_data_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field id from log_request_data message - * - * @return Log id (from LOG_ENTRY reply) - */ -static inline uint16_t mavlink_msg_log_request_data_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field ofs from log_request_data message - * - * @return Offset into the log - */ -static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from log_request_data message - * - * @return Number of bytes - */ -static inline uint32_t mavlink_msg_log_request_data_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Decode a log_request_data message into a struct - * - * @param msg The message to decode - * @param log_request_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_data_decode(const mavlink_message_t* msg, mavlink_log_request_data_t* log_request_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_request_data->ofs = mavlink_msg_log_request_data_get_ofs(msg); - log_request_data->count = mavlink_msg_log_request_data_get_count(msg); - log_request_data->id = mavlink_msg_log_request_data_get_id(msg); - log_request_data->target_system = mavlink_msg_log_request_data_get_target_system(msg); - log_request_data->target_component = mavlink_msg_log_request_data_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN? msg->len : MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN; - memset(log_request_data, 0, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); - memcpy(log_request_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h b/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h deleted file mode 100644 index dc0c1e5..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE LOG_REQUEST_END PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_END 122 - -MAVPACKED( -typedef struct __mavlink_log_request_end_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_request_end_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2 -#define MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN 2 -#define MAVLINK_MSG_ID_122_LEN 2 -#define MAVLINK_MSG_ID_122_MIN_LEN 2 - -#define MAVLINK_MSG_ID_LOG_REQUEST_END_CRC 203 -#define MAVLINK_MSG_ID_122_CRC 203 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_END { \ - 122, \ - "LOG_REQUEST_END", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_request_end_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_request_end_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_END { \ - "LOG_REQUEST_END", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_request_end_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_request_end_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_request_end message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_end_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -} - -/** - * @brief Pack a log_request_end message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_end_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -} - -/** - * @brief Encode a log_request_end struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_end C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_end_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) -{ - return mavlink_msg_log_request_end_pack(system_id, component_id, msg, log_request_end->target_system, log_request_end->target_component); -} - -/** - * @brief Encode a log_request_end struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_end C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_end_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) -{ - return mavlink_msg_log_request_end_pack_chan(system_id, component_id, chan, msg, log_request_end->target_system, log_request_end->target_component); -} - -/** - * @brief Send a log_request_end message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_end_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_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_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#endif -} - -/** - * @brief Send a log_request_end message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_request_end_send_struct(mavlink_channel_t chan, const mavlink_log_request_end_t* log_request_end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_request_end_send(chan, log_request_end->target_system, log_request_end->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)log_request_end, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_END_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_end_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - mavlink_log_request_end_t *packet = (mavlink_log_request_end_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_END UNPACKING - - -/** - * @brief Get field target_system from log_request_end message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_end_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from log_request_end message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_end_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a log_request_end message into a struct - * - * @param msg The message to decode - * @param log_request_end C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_end_decode(const mavlink_message_t* msg, mavlink_log_request_end_t* log_request_end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_request_end->target_system = mavlink_msg_log_request_end_get_target_system(msg); - log_request_end->target_component = mavlink_msg_log_request_end_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_REQUEST_END_LEN? msg->len : MAVLINK_MSG_ID_LOG_REQUEST_END_LEN; - memset(log_request_end, 0, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); - memcpy(log_request_end, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h b/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h deleted file mode 100644 index f4b00c9..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE LOG_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST 117 - -MAVPACKED( -typedef struct __mavlink_log_request_list_t { - uint16_t start; /*< First log id (0 for first available)*/ - uint16_t end; /*< Last log id (0xffff for last available)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_request_list_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6 -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN 6 -#define MAVLINK_MSG_ID_117_LEN 6 -#define MAVLINK_MSG_ID_117_MIN_LEN 6 - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC 128 -#define MAVLINK_MSG_ID_117_CRC 128 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \ - 117, \ - "LOG_REQUEST_LIST", \ - 4, \ - { { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ - { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \ - "LOG_REQUEST_LIST", \ - 4, \ - { { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ - { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -} - -/** - * @brief Pack a log_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t start,uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -} - -/** - * @brief Encode a log_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) -{ - return mavlink_msg_log_request_list_pack(system_id, component_id, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); -} - -/** - * @brief Encode a log_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) -{ - return mavlink_msg_log_request_list_pack_chan(system_id, component_id, chan, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); -} - -/** - * @brief Send a log_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _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_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#endif -} - -/** - * @brief Send a log_request_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_request_list_send_struct(mavlink_channel_t chan, const mavlink_log_request_list_t* log_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_request_list_send(chan, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)log_request_list, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _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_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - mavlink_log_request_list_t *packet = (mavlink_log_request_list_t *)msgbuf; - packet->start = start; - packet->end = end; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from log_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from log_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start from log_request_list message - * - * @return First log id (0 for first available) - */ -static inline uint16_t mavlink_msg_log_request_list_get_start(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field end from log_request_list message - * - * @return Last log id (0xffff for last available) - */ -static inline uint16_t mavlink_msg_log_request_list_get_end(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a log_request_list message into a struct - * - * @param msg The message to decode - * @param log_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_list_decode(const mavlink_message_t* msg, mavlink_log_request_list_t* log_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_request_list->start = mavlink_msg_log_request_list_get_start(msg); - log_request_list->end = mavlink_msg_log_request_list_get_end(msg); - log_request_list->target_system = mavlink_msg_log_request_list_get_target_system(msg); - log_request_list->target_component = mavlink_msg_log_request_list_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN; - memset(log_request_list, 0, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); - memcpy(log_request_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_manual_control.h b/include/mavlink/v1.0/common/mavlink_msg_manual_control.h deleted file mode 100644 index 05a2566..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_manual_control.h +++ /dev/null @@ -1,338 +0,0 @@ -#pragma once -// MESSAGE MANUAL_CONTROL PACKING - -#define MAVLINK_MSG_ID_MANUAL_CONTROL 69 - -MAVPACKED( -typedef struct __mavlink_manual_control_t { - int16_t x; /*< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.*/ - int16_t y; /*< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.*/ - int16_t z; /*< Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.*/ - int16_t r; /*< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.*/ - uint16_t buttons; /*< A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.*/ - uint8_t target; /*< The system to be controlled.*/ -}) mavlink_manual_control_t; - -#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11 -#define MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN 11 -#define MAVLINK_MSG_ID_69_LEN 11 -#define MAVLINK_MSG_ID_69_MIN_LEN 11 - -#define MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243 -#define MAVLINK_MSG_ID_69_CRC 243 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ - 69, \ - "MANUAL_CONTROL", \ - 6, \ - { { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \ - { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \ - { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \ - { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ - "MANUAL_CONTROL", \ - 6, \ - { { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \ - { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \ - { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \ - { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ - } \ -} -#endif - -/** - * @brief Pack a manual_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - - 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, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -} - -/** - * @brief Pack a manual_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - - 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, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -} - -/** - * @brief Encode a manual_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param manual_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) -{ - return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); -} - -/** - * @brief Encode a manual_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param manual_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) -{ - return mavlink_msg_manual_control_pack_chan(system_id, component_id, chan, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); -} - -/** - * @brief Send a manual_control message - * @param chan MAVLink channel to send the message - * - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int16_t(buf, 6, r); - _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, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#endif -} - -/** - * @brief Send a manual_control message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_manual_control_send_struct(mavlink_channel_t chan, const mavlink_manual_control_t* manual_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_manual_control_send(chan, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)manual_control, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MANUAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_manual_control_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_int16_t(buf, 0, x); - _mav_put_int16_t(buf, 2, y); - _mav_put_int16_t(buf, 4, z); - _mav_put_int16_t(buf, 6, r); - _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, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - mavlink_manual_control_t *packet = (mavlink_manual_control_t *)msgbuf; - packet->x = x; - packet->y = y; - packet->z = z; - packet->r = r; - packet->buttons = buttons; - packet->target = target; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MANUAL_CONTROL UNPACKING - - -/** - * @brief Get field target from manual_control message - * - * @return The system to be controlled. - */ -static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field x from manual_control message - * - * @return X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field y from manual_control message - * - * @return Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Get field z from manual_control message - * - * @return Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - */ -static inline int16_t mavlink_msg_manual_control_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field r from manual_control message - * - * @return R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_r(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field buttons from manual_control message - * - * @return A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - */ -static inline uint16_t mavlink_msg_manual_control_get_buttons(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Decode a manual_control message into a struct - * - * @param msg The message to decode - * @param manual_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - manual_control->x = mavlink_msg_manual_control_get_x(msg); - manual_control->y = mavlink_msg_manual_control_get_y(msg); - manual_control->z = mavlink_msg_manual_control_get_z(msg); - manual_control->r = mavlink_msg_manual_control_get_r(msg); - manual_control->buttons = mavlink_msg_manual_control_get_buttons(msg); - manual_control->target = mavlink_msg_manual_control_get_target(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MANUAL_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_MANUAL_CONTROL_LEN; - memset(manual_control, 0, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); - memcpy(manual_control, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h b/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h deleted file mode 100644 index 04d50a8..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE MANUAL_SETPOINT PACKING - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT 81 - -MAVPACKED( -typedef struct __mavlink_manual_setpoint_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float roll; /*< Desired roll rate in radians per second*/ - float pitch; /*< Desired pitch rate in radians per second*/ - float yaw; /*< Desired yaw rate in radians per second*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1*/ - uint8_t mode_switch; /*< Flight mode switch position, 0.. 255*/ - uint8_t manual_override_switch; /*< Override mode switch position, 0.. 255*/ -}) mavlink_manual_setpoint_t; - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22 -#define MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN 22 -#define MAVLINK_MSG_ID_81_LEN 22 -#define MAVLINK_MSG_ID_81_MIN_LEN 22 - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC 106 -#define MAVLINK_MSG_ID_81_CRC 106 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \ - 81, \ - "MANUAL_SETPOINT", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \ - { "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \ - { "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \ - "MANUAL_SETPOINT", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \ - { "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \ - { "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \ - } \ -} -#endif - -/** - * @brief Pack a manual_setpoint 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_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - - 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; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.mode_switch = mode_switch; - packet.manual_override_switch = manual_override_switch; - - 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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -} - -/** - * @brief Pack a manual_setpoint message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - - 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; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.mode_switch = mode_switch; - packet.manual_override_switch = manual_override_switch; - - 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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -} - -/** - * @brief Encode a manual_setpoint struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param manual_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) -{ - return mavlink_msg_manual_setpoint_pack(system_id, component_id, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); -} - -/** - * @brief Encode a manual_setpoint struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param manual_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) -{ - return mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, chan, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); -} - -/** - * @brief Send a manual_setpoint message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - mavlink_manual_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - 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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#endif -} - -/** - * @brief Send a manual_setpoint message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_manual_setpoint_send_struct(mavlink_channel_t chan, const mavlink_manual_setpoint_t* manual_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_manual_setpoint_send(chan, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)manual_setpoint, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_manual_setpoint_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - mavlink_manual_setpoint_t *packet = (mavlink_manual_setpoint_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->thrust = thrust; - 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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MANUAL_SETPOINT UNPACKING - - -/** - * @brief Get field time_boot_ms from manual_setpoint message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll from manual_setpoint message - * - * @return Desired roll rate in radians per second - */ -static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch from manual_setpoint message - * - * @return Desired pitch rate in radians per second - */ -static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from manual_setpoint message - * - * @return Desired yaw rate in radians per second - */ -static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field thrust from manual_setpoint message - * - * @return Collective thrust, normalized to 0 .. 1 - */ -static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field mode_switch from manual_setpoint message - * - * @return Flight mode switch position, 0.. 255 - */ -static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field manual_override_switch from manual_setpoint message - * - * @return Override mode switch position, 0.. 255 - */ -static inline uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a manual_setpoint message into a struct - * - * @param msg The message to decode - * @param manual_setpoint C-struct to decode the message contents into - */ -static inline void mavlink_msg_manual_setpoint_decode(const mavlink_message_t* msg, mavlink_manual_setpoint_t* manual_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - manual_setpoint->time_boot_ms = mavlink_msg_manual_setpoint_get_time_boot_ms(msg); - manual_setpoint->roll = mavlink_msg_manual_setpoint_get_roll(msg); - manual_setpoint->pitch = mavlink_msg_manual_setpoint_get_pitch(msg); - manual_setpoint->yaw = mavlink_msg_manual_setpoint_get_yaw(msg); - manual_setpoint->thrust = mavlink_msg_manual_setpoint_get_thrust(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN? msg->len : MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN; - memset(manual_setpoint, 0, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); - memcpy(manual_setpoint, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h b/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h deleted file mode 100644 index efc0e62..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE MEMORY_VECT PACKING - -#define MAVLINK_MSG_ID_MEMORY_VECT 249 - -MAVPACKED( -typedef struct __mavlink_memory_vect_t { - uint16_t address; /*< Starting address of the debug variables*/ - uint8_t ver; /*< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below*/ - uint8_t type; /*< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14*/ - int8_t value[32]; /*< Memory contents at specified address*/ -}) mavlink_memory_vect_t; - -#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 -#define MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN 36 -#define MAVLINK_MSG_ID_249_LEN 36 -#define MAVLINK_MSG_ID_249_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ - 249, \ - "MEMORY_VECT", \ - 4, \ - { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ - { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ - { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ - "MEMORY_VECT", \ - 4, \ - { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ - { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ - { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ - } \ -} -#endif - -/** - * @brief Pack a memory_vect 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 address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -} - -/** - * @brief Pack a memory_vect message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t address,uint8_t ver,uint8_t type,const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -} - -/** - * @brief Encode a memory_vect struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param memory_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) -{ - return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); -} - -/** - * @brief Encode a memory_vect struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param memory_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_memory_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) -{ - return mavlink_msg_memory_vect_pack_chan(system_id, component_id, chan, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); -} - -/** - * @brief Send a memory_vect message - * @param chan MAVLink channel to send the message - * - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#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, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#endif -} - -/** - * @brief Send a memory_vect message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_memory_vect_send_struct(mavlink_channel_t chan, const mavlink_memory_vect_t* memory_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_memory_vect_send(chan, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)memory_vect, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MEMORY_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_memory_vect_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#else - mavlink_memory_vect_t *packet = (mavlink_memory_vect_t *)msgbuf; - 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, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MEMORY_VECT UNPACKING - - -/** - * @brief Get field address from memory_vect message - * - * @return Starting address of the debug variables - */ -static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field ver from memory_vect message - * - * @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - */ -static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field type from memory_vect message - * - * @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - */ -static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field value from memory_vect message - * - * @return Memory contents at specified address - */ -static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value) -{ - return _MAV_RETURN_int8_t_array(msg, value, 32, 4); -} - -/** - * @brief Decode a memory_vect message into a struct - * - * @param msg The message to decode - * @param memory_vect C-struct to decode the message contents into - */ -static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - memory_vect->address = mavlink_msg_memory_vect_get_address(msg); - memory_vect->ver = mavlink_msg_memory_vect_get_ver(msg); - memory_vect->type = mavlink_msg_memory_vect_get_type(msg); - mavlink_msg_memory_vect_get_value(msg, memory_vect->value); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MEMORY_VECT_LEN? msg->len : MAVLINK_MSG_ID_MEMORY_VECT_LEN; - memset(memory_vect, 0, MAVLINK_MSG_ID_MEMORY_VECT_LEN); - memcpy(memory_vect, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_message_interval.h b/include/mavlink/v1.0/common/mavlink_msg_message_interval.h deleted file mode 100644 index 95b501f..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_message_interval.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE MESSAGE_INTERVAL PACKING - -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL 244 - -MAVPACKED( -typedef struct __mavlink_message_interval_t { - int32_t interval_us; /*< The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.*/ - uint16_t message_id; /*< The ID of the requested MAVLink message. v1.0 is limited to 254 messages.*/ -}) mavlink_message_interval_t; - -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN 6 -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN 6 -#define MAVLINK_MSG_ID_244_LEN 6 -#define MAVLINK_MSG_ID_244_MIN_LEN 6 - -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC 95 -#define MAVLINK_MSG_ID_244_CRC 95 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL { \ - 244, \ - "MESSAGE_INTERVAL", \ - 2, \ - { { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ - { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL { \ - "MESSAGE_INTERVAL", \ - 2, \ - { { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ - { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ - } \ -} -#endif - -/** - * @brief Pack a message_interval 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 message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_message_interval_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t message_id, int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#else - mavlink_message_interval_t packet; - packet.interval_us = interval_us; - packet.message_id = message_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -} - -/** - * @brief Pack a message_interval message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_message_interval_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t message_id,int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#else - mavlink_message_interval_t packet; - packet.interval_us = interval_us; - packet.message_id = message_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -} - -/** - * @brief Encode a message_interval struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param message_interval C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_message_interval_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval) -{ - return mavlink_msg_message_interval_pack(system_id, component_id, msg, message_interval->message_id, message_interval->interval_us); -} - -/** - * @brief Encode a message_interval struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param message_interval C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_message_interval_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval) -{ - return mavlink_msg_message_interval_pack_chan(system_id, component_id, chan, msg, message_interval->message_id, message_interval->interval_us); -} - -/** - * @brief Send a message_interval message - * @param chan MAVLink channel to send the message - * - * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_message_interval_send(mavlink_channel_t chan, uint16_t message_id, int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#else - mavlink_message_interval_t packet; - packet.interval_us = interval_us; - packet.message_id = message_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)&packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#endif -} - -/** - * @brief Send a message_interval message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_message_interval_send_struct(mavlink_channel_t chan, const mavlink_message_interval_t* message_interval) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_message_interval_send(chan, message_interval->message_id, message_interval->interval_us); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)message_interval, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_message_interval_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t message_id, int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#else - mavlink_message_interval_t *packet = (mavlink_message_interval_t *)msgbuf; - packet->interval_us = interval_us; - packet->message_id = message_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MESSAGE_INTERVAL UNPACKING - - -/** - * @brief Get field message_id from message_interval message - * - * @return The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - */ -static inline uint16_t mavlink_msg_message_interval_get_message_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field interval_us from message_interval message - * - * @return The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - */ -static inline int32_t mavlink_msg_message_interval_get_interval_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Decode a message_interval message into a struct - * - * @param msg The message to decode - * @param message_interval C-struct to decode the message contents into - */ -static inline void mavlink_msg_message_interval_decode(const mavlink_message_t* msg, mavlink_message_interval_t* message_interval) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - message_interval->interval_us = mavlink_msg_message_interval_get_interval_us(msg); - message_interval->message_id = mavlink_msg_message_interval_get_message_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN? msg->len : MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN; - memset(message_interval, 0, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); - memcpy(message_interval, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h b/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h deleted file mode 100644 index 9616a0f..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE MISSION_ACK PACKING - -#define MAVLINK_MSG_ID_MISSION_ACK 47 - -MAVPACKED( -typedef struct __mavlink_mission_ack_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t type; /*< See MAV_MISSION_RESULT enum*/ -}) mavlink_mission_ack_t; - -#define MAVLINK_MSG_ID_MISSION_ACK_LEN 3 -#define MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN 3 -#define MAVLINK_MSG_ID_47_LEN 3 -#define MAVLINK_MSG_ID_47_MIN_LEN 3 - -#define MAVLINK_MSG_ID_MISSION_ACK_CRC 153 -#define MAVLINK_MSG_ID_47_CRC 153 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ - 47, \ - "MISSION_ACK", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ - "MISSION_ACK", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -} - -/** - * @brief Pack a mission_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -} - -/** - * @brief Encode a mission_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) -{ - return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type); -} - -/** - * @brief Encode a mission_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) -{ - return mavlink_msg_mission_ack_pack_chan(system_id, component_id, chan, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type); -} - -/** - * @brief Send a mission_ack message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#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, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#endif -} - -/** - * @brief Send a mission_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_ack_send_struct(mavlink_channel_t chan, const mavlink_mission_ack_t* mission_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_ack_send(chan, mission_ack->target_system, mission_ack->target_component, mission_ack->type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)mission_ack, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_ack_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#else - mavlink_mission_ack_t *packet = (mavlink_mission_ack_t *)msgbuf; - 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, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ACK UNPACKING - - -/** - * @brief Get field target_system from mission_ack message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_ack message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field type from mission_ack message - * - * @return See MAV_MISSION_RESULT enum - */ -static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a mission_ack message into a struct - * - * @param msg The message to decode - * @param mission_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg, mavlink_mission_ack_t* mission_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_ack->target_system = mavlink_msg_mission_ack_get_target_system(msg); - mission_ack->target_component = mavlink_msg_mission_ack_get_target_component(msg); - mission_ack->type = mavlink_msg_mission_ack_get_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ACK_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ACK_LEN; - memset(mission_ack, 0, MAVLINK_MSG_ID_MISSION_ACK_LEN); - memcpy(mission_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h b/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h deleted file mode 100644 index fa7e20e..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE MISSION_CLEAR_ALL PACKING - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45 - -MAVPACKED( -typedef struct __mavlink_mission_clear_all_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_clear_all_t; - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2 -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN 2 -#define MAVLINK_MSG_ID_45_LEN 2 -#define MAVLINK_MSG_ID_45_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC 232 -#define MAVLINK_MSG_ID_45_CRC 232 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ - 45, \ - "MISSION_CLEAR_ALL", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ - "MISSION_CLEAR_ALL", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_clear_all message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -} - -/** - * @brief Pack a mission_clear_all message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -} - -/** - * @brief Encode a mission_clear_all struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_clear_all C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) -{ - return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component); -} - -/** - * @brief Encode a mission_clear_all struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_clear_all C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_clear_all_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) -{ - return mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, chan, msg, mission_clear_all->target_system, mission_clear_all->target_component); -} - -/** - * @brief Send a mission_clear_all message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#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, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#endif -} - -/** - * @brief Send a mission_clear_all message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_clear_all_send_struct(mavlink_channel_t chan, const mavlink_mission_clear_all_t* mission_clear_all) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_clear_all_send(chan, mission_clear_all->target_system, mission_clear_all->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)mission_clear_all, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_clear_all_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#else - mavlink_mission_clear_all_t *packet = (mavlink_mission_clear_all_t *)msgbuf; - 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, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_CLEAR_ALL UNPACKING - - -/** - * @brief Get field target_system from mission_clear_all message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_clear_all message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a mission_clear_all message into a struct - * - * @param msg The message to decode - * @param mission_clear_all C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t* msg, mavlink_mission_clear_all_t* mission_clear_all) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN? msg->len : MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN; - memset(mission_clear_all, 0, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); - memcpy(mission_clear_all, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_count.h b/include/mavlink/v1.0/common/mavlink_msg_mission_count.h deleted file mode 100644 index 6ba66ff..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_count.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE MISSION_COUNT PACKING - -#define MAVLINK_MSG_ID_MISSION_COUNT 44 - -MAVPACKED( -typedef struct __mavlink_mission_count_t { - uint16_t count; /*< Number of mission items in the sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_count_t; - -#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4 -#define MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN 4 -#define MAVLINK_MSG_ID_44_LEN 4 -#define MAVLINK_MSG_ID_44_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_COUNT_CRC 221 -#define MAVLINK_MSG_ID_44_CRC 221 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ - 44, \ - "MISSION_COUNT", \ - 3, \ - { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ - "MISSION_COUNT", \ - 3, \ - { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_count message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -} - -/** - * @brief Pack a mission_count message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -} - -/** - * @brief Encode a mission_count struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_count C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) -{ - return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count); -} - -/** - * @brief Encode a mission_count struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_count C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_count_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) -{ - return mavlink_msg_mission_count_pack_chan(system_id, component_id, chan, msg, mission_count->target_system, mission_count->target_component, mission_count->count); -} - -/** - * @brief Send a mission_count message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#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, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#endif -} - -/** - * @brief Send a mission_count message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_count_send_struct(mavlink_channel_t chan, const mavlink_mission_count_t* mission_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_count_send(chan, mission_count->target_system, mission_count->target_component, mission_count->count); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)mission_count, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_COUNT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#else - mavlink_mission_count_t *packet = (mavlink_mission_count_t *)msgbuf; - 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, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_COUNT UNPACKING - - -/** - * @brief Get field target_system from mission_count message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_count message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field count from mission_count message - * - * @return Number of mission items in the sequence - */ -static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_count message into a struct - * - * @param msg The message to decode - * @param mission_count C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_count->count = mavlink_msg_mission_count_get_count(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 - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_COUNT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_COUNT_LEN; - memset(mission_count, 0, MAVLINK_MSG_ID_MISSION_COUNT_LEN); - memcpy(mission_count, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_current.h b/include/mavlink/v1.0/common/mavlink_msg_mission_current.h deleted file mode 100644 index 802632d..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_current.h +++ /dev/null @@ -1,213 +0,0 @@ -#pragma once -// MESSAGE MISSION_CURRENT PACKING - -#define MAVLINK_MSG_ID_MISSION_CURRENT 42 - -MAVPACKED( -typedef struct __mavlink_mission_current_t { - uint16_t seq; /*< Sequence*/ -}) mavlink_mission_current_t; - -#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2 -#define MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN 2 -#define MAVLINK_MSG_ID_42_LEN 2 -#define MAVLINK_MSG_ID_42_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_CURRENT_CRC 28 -#define MAVLINK_MSG_ID_42_CRC 28 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ - 42, \ - "MISSION_CURRENT", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ - "MISSION_CURRENT", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_current 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 seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - 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, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -} - -/** - * @brief Pack a mission_current message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - 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, 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, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -} - -/** - * @brief Encode a mission_current struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) -{ - return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq); -} - -/** - * @brief Encode a mission_current struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) -{ - return mavlink_msg_mission_current_pack_chan(system_id, component_id, chan, msg, mission_current->seq); -} - -/** - * @brief Send a mission_current message - * @param chan MAVLink channel to send the message - * - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - mavlink_mission_current_t packet; - packet.seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#endif -} - -/** - * @brief Send a mission_current message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_current_send_struct(mavlink_channel_t chan, const mavlink_mission_current_t* mission_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_current_send(chan, mission_current->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)mission_current, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - mavlink_mission_current_t *packet = (mavlink_mission_current_t *)msgbuf; - packet->seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_CURRENT UNPACKING - - -/** - * @brief Get field seq from mission_current message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_current message into a struct - * - * @param msg The message to decode - * @param mission_current C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_current->seq = mavlink_msg_mission_current_get_seq(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_CURRENT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_CURRENT_LEN; - memset(mission_current, 0, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); - memcpy(mission_current, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_item.h b/include/mavlink/v1.0/common/mavlink_msg_mission_item.h deleted file mode 100644 index afcf519..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_item.h +++ /dev/null @@ -1,538 +0,0 @@ -#pragma once -// MESSAGE MISSION_ITEM PACKING - -#define MAVLINK_MSG_ID_MISSION_ITEM 39 - -MAVPACKED( -typedef struct __mavlink_mission_item_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - float x; /*< PARAM5 / local: x position, global: latitude*/ - float y; /*< PARAM6 / y position: global: longitude*/ - float z; /*< PARAM7 / z position: global: altitude (relative or absolute, depending on frame.*/ - uint16_t seq; /*< Sequence*/ - uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/ - uint8_t current; /*< false:0, true:1*/ - uint8_t autocontinue; /*< autocontinue to next wp*/ -}) mavlink_mission_item_t; - -#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37 -#define MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN 37 -#define MAVLINK_MSG_ID_39_LEN 37 -#define MAVLINK_MSG_ID_39_MIN_LEN 37 - -#define MAVLINK_MSG_ID_MISSION_ITEM_CRC 254 -#define MAVLINK_MSG_ID_39_CRC 254 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ - 39, \ - "MISSION_ITEM", \ - 14, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ - "MISSION_ITEM", \ - 14, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_item message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - 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, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -} - -/** - * @brief Pack a mission_item message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - 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, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -} - -/** - * @brief Encode a mission_item struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_item C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) -{ - return mavlink_msg_mission_item_pack(system_id, component_id, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z); -} - -/** - * @brief Encode a mission_item struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_item C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) -{ - return mavlink_msg_mission_item_pack_chan(system_id, component_id, chan, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z); -} - -/** - * @brief Send a mission_item message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _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, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#endif -} - -/** - * @brief Send a mission_item message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_item_send_struct(mavlink_channel_t chan, const mavlink_mission_item_t* mission_item) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_item_send(chan, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)mission_item, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ITEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_item_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _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, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - mavlink_mission_item_t *packet = (mavlink_mission_item_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->x = x; - packet->y = y; - packet->z = z; - packet->seq = seq; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - packet->current = current; - packet->autocontinue = autocontinue; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ITEM UNPACKING - - -/** - * @brief Get field target_system from mission_item message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field target_component from mission_item message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field seq from mission_item message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field frame from mission_item message - * - * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - */ -static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field command from mission_item message - * - * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - */ -static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field current from mission_item message - * - * @return false:0, true:1 - */ -static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field autocontinue from mission_item message - * - * @return autocontinue to next wp - */ -static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field param1 from mission_item message - * - * @return PARAM1, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from mission_item message - * - * @return PARAM2, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from mission_item message - * - * @return PARAM3, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from mission_item message - * - * @return PARAM4, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field x from mission_item message - * - * @return PARAM5 / local: x position, global: latitude - */ -static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field y from mission_item message - * - * @return PARAM6 / y position: global: longitude - */ -static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field z from mission_item message - * - * @return PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - */ -static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a mission_item message into a struct - * - * @param msg The message to decode - * @param mission_item C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* msg, mavlink_mission_item_t* mission_item) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_item->param1 = mavlink_msg_mission_item_get_param1(msg); - mission_item->param2 = mavlink_msg_mission_item_get_param2(msg); - mission_item->param3 = mavlink_msg_mission_item_get_param3(msg); - mission_item->param4 = mavlink_msg_mission_item_get_param4(msg); - mission_item->x = mavlink_msg_mission_item_get_x(msg); - mission_item->y = mavlink_msg_mission_item_get_y(msg); - mission_item->z = mavlink_msg_mission_item_get_z(msg); - mission_item->seq = mavlink_msg_mission_item_get_seq(msg); - mission_item->command = mavlink_msg_mission_item_get_command(msg); - mission_item->target_system = mavlink_msg_mission_item_get_target_system(msg); - mission_item->target_component = mavlink_msg_mission_item_get_target_component(msg); - mission_item->frame = mavlink_msg_mission_item_get_frame(msg); - mission_item->current = mavlink_msg_mission_item_get_current(msg); - mission_item->autocontinue = mavlink_msg_mission_item_get_autocontinue(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_LEN; - memset(mission_item, 0, MAVLINK_MSG_ID_MISSION_ITEM_LEN); - memcpy(mission_item, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_item_int.h b/include/mavlink/v1.0/common/mavlink_msg_mission_item_int.h deleted file mode 100644 index 6684723..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_item_int.h +++ /dev/null @@ -1,538 +0,0 @@ -#pragma once -// MESSAGE MISSION_ITEM_INT PACKING - -#define MAVLINK_MSG_ID_MISSION_ITEM_INT 73 - -MAVPACKED( -typedef struct __mavlink_mission_item_int_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ - int32_t y; /*< PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7*/ - float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ - uint16_t seq; /*< Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).*/ - uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/ - uint8_t current; /*< false:0, true:1*/ - uint8_t autocontinue; /*< autocontinue to next wp*/ -}) mavlink_mission_item_int_t; - -#define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 37 -#define MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN 37 -#define MAVLINK_MSG_ID_73_LEN 37 -#define MAVLINK_MSG_ID_73_MIN_LEN 37 - -#define MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC 38 -#define MAVLINK_MSG_ID_73_CRC 38 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \ - 73, \ - "MISSION_ITEM_INT", \ - 14, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \ - "MISSION_ITEM_INT", \ - 14, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_item_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#else - mavlink_mission_item_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -} - -/** - * @brief Pack a mission_item_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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,int32_t x,int32_t y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#else - mavlink_mission_item_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -} - -/** - * @brief Encode a mission_item_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_item_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int) -{ - return mavlink_msg_mission_item_int_pack(system_id, component_id, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z); -} - -/** - * @brief Encode a mission_item_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_item_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int) -{ - return mavlink_msg_mission_item_int_pack_chan(system_id, component_id, chan, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z); -} - -/** - * @brief Send a mission_item_int message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_item_int_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, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _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_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#else - mavlink_mission_item_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#endif -} - -/** - * @brief Send a mission_item_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_item_int_send_struct(mavlink_channel_t chan, const mavlink_mission_item_int_t* mission_item_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_item_int_send(chan, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)mission_item_int, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgbuf, 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, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _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_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#else - mavlink_mission_item_int_t *packet = (mavlink_mission_item_int_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->x = x; - packet->y = y; - packet->z = z; - packet->seq = seq; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - packet->current = current; - packet->autocontinue = autocontinue; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ITEM_INT UNPACKING - - -/** - * @brief Get field target_system from mission_item_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_item_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field target_component from mission_item_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_item_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field seq from mission_item_int message - * - * @return Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - */ -static inline uint16_t mavlink_msg_mission_item_int_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field frame from mission_item_int message - * - * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - */ -static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field command from mission_item_int message - * - * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - */ -static inline uint16_t mavlink_msg_mission_item_int_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field current from mission_item_int message - * - * @return false:0, true:1 - */ -static inline uint8_t mavlink_msg_mission_item_int_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field autocontinue from mission_item_int message - * - * @return autocontinue to next wp - */ -static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field param1 from mission_item_int message - * - * @return PARAM1, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from mission_item_int message - * - * @return PARAM2, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from mission_item_int message - * - * @return PARAM3, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from mission_item_int message - * - * @return PARAM4, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field x from mission_item_int message - * - * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - */ -static inline int32_t mavlink_msg_mission_item_int_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field y from mission_item_int message - * - * @return PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - */ -static inline int32_t mavlink_msg_mission_item_int_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field z from mission_item_int message - * - * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - */ -static inline float mavlink_msg_mission_item_int_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a mission_item_int message into a struct - * - * @param msg The message to decode - * @param mission_item_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_item_int_decode(const mavlink_message_t* msg, mavlink_mission_item_int_t* mission_item_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_item_int->param1 = mavlink_msg_mission_item_int_get_param1(msg); - mission_item_int->param2 = mavlink_msg_mission_item_int_get_param2(msg); - mission_item_int->param3 = mavlink_msg_mission_item_int_get_param3(msg); - mission_item_int->param4 = mavlink_msg_mission_item_int_get_param4(msg); - mission_item_int->x = mavlink_msg_mission_item_int_get_x(msg); - mission_item_int->y = mavlink_msg_mission_item_int_get_y(msg); - mission_item_int->z = mavlink_msg_mission_item_int_get_z(msg); - mission_item_int->seq = mavlink_msg_mission_item_int_get_seq(msg); - mission_item_int->command = mavlink_msg_mission_item_int_get_command(msg); - mission_item_int->target_system = mavlink_msg_mission_item_int_get_target_system(msg); - mission_item_int->target_component = mavlink_msg_mission_item_int_get_target_component(msg); - mission_item_int->frame = mavlink_msg_mission_item_int_get_frame(msg); - mission_item_int->current = mavlink_msg_mission_item_int_get_current(msg); - mission_item_int->autocontinue = mavlink_msg_mission_item_int_get_autocontinue(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN; - memset(mission_item_int, 0, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); - memcpy(mission_item_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h b/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h deleted file mode 100644 index 1ad0e29..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h +++ /dev/null @@ -1,213 +0,0 @@ -#pragma once -// MESSAGE MISSION_ITEM_REACHED PACKING - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46 - -MAVPACKED( -typedef struct __mavlink_mission_item_reached_t { - uint16_t seq; /*< Sequence*/ -}) mavlink_mission_item_reached_t; - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN 2 -#define MAVLINK_MSG_ID_46_LEN 2 -#define MAVLINK_MSG_ID_46_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC 11 -#define MAVLINK_MSG_ID_46_CRC 11 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ - 46, \ - "MISSION_ITEM_REACHED", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ - "MISSION_ITEM_REACHED", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_item_reached 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 seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - 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, 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, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -} - -/** - * @brief Pack a mission_item_reached message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - 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, 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, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -} - -/** - * @brief Encode a mission_item_reached struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_item_reached C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) -{ - return mavlink_msg_mission_item_reached_pack(system_id, component_id, msg, mission_item_reached->seq); -} - -/** - * @brief Encode a mission_item_reached struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_item_reached C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_reached_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) -{ - return mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, chan, msg, mission_item_reached->seq); -} - -/** - * @brief Send a mission_item_reached message - * @param chan MAVLink channel to send the message - * - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#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, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#endif -} - -/** - * @brief Send a mission_item_reached message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_item_reached_send_struct(mavlink_channel_t chan, const mavlink_mission_item_reached_t* mission_item_reached) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_item_reached_send(chan, mission_item_reached->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)mission_item_reached, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_item_reached_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#else - mavlink_mission_item_reached_t *packet = (mavlink_mission_item_reached_t *)msgbuf; - packet->seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ITEM_REACHED UNPACKING - - -/** - * @brief Get field seq from mission_item_reached message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_item_reached_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_item_reached message into a struct - * - * @param msg The message to decode - * @param mission_item_reached C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_item_reached_decode(const mavlink_message_t* msg, mavlink_mission_item_reached_t* mission_item_reached) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_item_reached->seq = mavlink_msg_mission_item_reached_get_seq(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN; - memset(mission_item_reached, 0, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); - memcpy(mission_item_reached, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_request.h b/include/mavlink/v1.0/common/mavlink_msg_mission_request.h deleted file mode 100644 index 9d6d48e..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_request.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST 40 - -MAVPACKED( -typedef struct __mavlink_mission_request_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_request_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4 -#define MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN 4 -#define MAVLINK_MSG_ID_40_LEN 4 -#define MAVLINK_MSG_ID_40_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230 -#define MAVLINK_MSG_ID_40_CRC 230 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ - 40, \ - "MISSION_REQUEST", \ - 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ - "MISSION_REQUEST", \ - 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -} - -/** - * @brief Pack a mission_request message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -} - -/** - * @brief Encode a mission_request struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) -{ - return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq); -} - -/** - * @brief Encode a mission_request struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) -{ - return mavlink_msg_mission_request_pack_chan(system_id, component_id, chan, msg, mission_request->target_system, mission_request->target_component, mission_request->seq); -} - -/** - * @brief Send a mission_request message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#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, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#endif -} - -/** - * @brief Send a mission_request message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_send_struct(mavlink_channel_t chan, const mavlink_mission_request_t* mission_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_send(chan, mission_request->target_system, mission_request->target_component, mission_request->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)mission_request, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#else - mavlink_mission_request_t *packet = (mavlink_mission_request_t *)msgbuf; - 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, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST UNPACKING - - -/** - * @brief Get field target_system from mission_request message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_request message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field seq from mission_request message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_request message into a struct - * - * @param msg The message to decode - * @param mission_request C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_request->seq = mavlink_msg_mission_request_get_seq(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_LEN; - memset(mission_request, 0, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); - memcpy(mission_request, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_request_int.h b/include/mavlink/v1.0/common/mavlink_msg_mission_request_int.h deleted file mode 100644 index 3257f94..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_request_int.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST_INT PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT 51 - -MAVPACKED( -typedef struct __mavlink_mission_request_int_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_request_int_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN 4 -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN 4 -#define MAVLINK_MSG_ID_51_LEN 4 -#define MAVLINK_MSG_ID_51_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC 196 -#define MAVLINK_MSG_ID_51_CRC 196 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \ - 51, \ - "MISSION_REQUEST_INT", \ - 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \ - "MISSION_REQUEST_INT", \ - 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_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, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#else - mavlink_mission_request_int_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -} - -/** - * @brief Pack a mission_request_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_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, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#else - mavlink_mission_request_int_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -} - -/** - * @brief Encode a mission_request_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int) -{ - return mavlink_msg_mission_request_int_pack(system_id, component_id, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq); -} - -/** - * @brief Encode a mission_request_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int) -{ - return mavlink_msg_mission_request_int_pack_chan(system_id, component_id, chan, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq); -} - -/** - * @brief Send a mission_request_int message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_request_int_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[MAVLINK_MSG_ID_MISSION_REQUEST_INT_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_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#else - mavlink_mission_request_int_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_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#endif -} - -/** - * @brief Send a mission_request_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_int_send_struct(mavlink_channel_t chan, const mavlink_mission_request_int_t* mission_request_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_int_send(chan, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)mission_request_int, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_int_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#else - mavlink_mission_request_int_t *packet = (mavlink_mission_request_int_t *)msgbuf; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST_INT UNPACKING - - -/** - * @brief Get field target_system from mission_request_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_request_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field seq from mission_request_int message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_request_int_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_request_int message into a struct - * - * @param msg The message to decode - * @param mission_request_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_int_decode(const mavlink_message_t* msg, mavlink_mission_request_int_t* mission_request_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_request_int->seq = mavlink_msg_mission_request_int_get_seq(msg); - mission_request_int->target_system = mavlink_msg_mission_request_int_get_target_system(msg); - mission_request_int->target_component = mavlink_msg_mission_request_int_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN; - memset(mission_request_int, 0, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); - memcpy(mission_request_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h b/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h deleted file mode 100644 index 64c211b..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43 - -MAVPACKED( -typedef struct __mavlink_mission_request_list_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_request_list_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2 -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN 2 -#define MAVLINK_MSG_ID_43_LEN 2 -#define MAVLINK_MSG_ID_43_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC 132 -#define MAVLINK_MSG_ID_43_CRC 132 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ - 43, \ - "MISSION_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ - "MISSION_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -} - -/** - * @brief Pack a mission_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -} - -/** - * @brief Encode a mission_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) -{ - return mavlink_msg_mission_request_list_pack(system_id, component_id, msg, mission_request_list->target_system, mission_request_list->target_component); -} - -/** - * @brief Encode a mission_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) -{ - return mavlink_msg_mission_request_list_pack_chan(system_id, component_id, chan, msg, mission_request_list->target_system, mission_request_list->target_component); -} - -/** - * @brief Send a mission_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#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, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#endif -} - -/** - * @brief Send a mission_request_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_list_send_struct(mavlink_channel_t chan, const mavlink_mission_request_list_t* mission_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_list_send(chan, mission_request_list->target_system, mission_request_list->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)mission_request_list, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#else - mavlink_mission_request_list_t *packet = (mavlink_mission_request_list_t *)msgbuf; - 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, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a mission_request_list message into a struct - * - * @param msg The message to decode - * @param mission_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_list_decode(const mavlink_message_t* msg, mavlink_mission_request_list_t* mission_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN; - memset(mission_request_list, 0, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); - memcpy(mission_request_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h b/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h deleted file mode 100644 index aa75763..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST_PARTIAL_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37 - -MAVPACKED( -typedef struct __mavlink_mission_request_partial_list_t { - int16_t start_index; /*< Start index, 0 by default*/ - int16_t end_index; /*< End index, -1 by default (-1: send list to end). Else a valid index of the list*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_request_partial_list_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6 -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN 6 -#define MAVLINK_MSG_ID_37_LEN 6 -#define MAVLINK_MSG_ID_37_MIN_LEN 6 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212 -#define MAVLINK_MSG_ID_37_CRC 212 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ - 37, \ - "MISSION_REQUEST_PARTIAL_LIST", \ - 4, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ - "MISSION_REQUEST_PARTIAL_LIST", \ - 4, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request_partial_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#else - mavlink_mission_request_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -} - -/** - * @brief Pack a mission_request_partial_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#else - mavlink_mission_request_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -} - -/** - * @brief Encode a mission_request_partial_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ - return mavlink_msg_mission_request_partial_list_pack(system_id, component_id, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index); -} - -/** - * @brief Encode a mission_request_partial_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ - return mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, chan, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index); -} - -/** - * @brief Send a mission_request_partial_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - mavlink_mission_request_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - 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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#endif -} - -/** - * @brief Send a mission_request_partial_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_partial_list_send_struct(mavlink_channel_t chan, const mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_partial_list_send(chan, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)mission_request_partial_list, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - mavlink_mission_request_partial_list_t *packet = (mavlink_mission_request_partial_list_t *)msgbuf; - packet->start_index = start_index; - packet->end_index = end_index; - 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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST_PARTIAL_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_request_partial_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from mission_request_partial_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start_index from mission_request_partial_list message - * - * @return Start index, 0 by default - */ -static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field end_index from mission_request_partial_list message - * - * @return End index, -1 by default (-1: send list to end). Else a valid index of the list - */ -static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Decode a mission_request_partial_list message into a struct - * - * @param msg The message to decode - * @param mission_request_partial_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_request_partial_list->start_index = mavlink_msg_mission_request_partial_list_get_start_index(msg); - mission_request_partial_list->end_index = mavlink_msg_mission_request_partial_list_get_end_index(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN; - memset(mission_request_partial_list, 0, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); - memcpy(mission_request_partial_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h b/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h deleted file mode 100644 index 50942fc..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE MISSION_SET_CURRENT PACKING - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT 41 - -MAVPACKED( -typedef struct __mavlink_mission_set_current_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_set_current_t; - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN 4 -#define MAVLINK_MSG_ID_41_LEN 4 -#define MAVLINK_MSG_ID_41_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC 28 -#define MAVLINK_MSG_ID_41_CRC 28 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ - 41, \ - "MISSION_SET_CURRENT", \ - 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ - "MISSION_SET_CURRENT", \ - 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_set_current message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -} - -/** - * @brief Pack a mission_set_current message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_set_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -} - -/** - * @brief Encode a mission_set_current struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_set_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) -{ - return mavlink_msg_mission_set_current_pack(system_id, component_id, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); -} - -/** - * @brief Encode a mission_set_current struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_set_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_set_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) -{ - return mavlink_msg_mission_set_current_pack_chan(system_id, component_id, chan, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); -} - -/** - * @brief Send a mission_set_current message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#endif -} - -/** - * @brief Send a mission_set_current message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_set_current_send_struct(mavlink_channel_t chan, const mavlink_mission_set_current_t* mission_set_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_set_current_send(chan, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)mission_set_current, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_set_current_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#else - mavlink_mission_set_current_t *packet = (mavlink_mission_set_current_t *)msgbuf; - 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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_SET_CURRENT UNPACKING - - -/** - * @brief Get field target_system from mission_set_current message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_set_current_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_set_current message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_set_current_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field seq from mission_set_current message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_set_current_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_set_current message into a struct - * - * @param msg The message to decode - * @param mission_set_current C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_set_current_decode(const mavlink_message_t* msg, mavlink_mission_set_current_t* mission_set_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_set_current->seq = mavlink_msg_mission_set_current_get_seq(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN; - memset(mission_set_current, 0, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); - memcpy(mission_set_current, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h b/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h deleted file mode 100644 index 756941b..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MISSION_WRITE_PARTIAL_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38 - -MAVPACKED( -typedef struct __mavlink_mission_write_partial_list_t { - int16_t start_index; /*< Start index, 0 by default and smaller / equal to the largest index of the current onboard list.*/ - int16_t end_index; /*< End index, equal or greater than start index.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_write_partial_list_t; - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6 -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN 6 -#define MAVLINK_MSG_ID_38_LEN 6 -#define MAVLINK_MSG_ID_38_MIN_LEN 6 - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9 -#define MAVLINK_MSG_ID_38_CRC 9 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ - 38, \ - "MISSION_WRITE_PARTIAL_LIST", \ - 4, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ - "MISSION_WRITE_PARTIAL_LIST", \ - 4, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_write_partial_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#else - mavlink_mission_write_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -} - -/** - * @brief Pack a mission_write_partial_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#else - mavlink_mission_write_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -} - -/** - * @brief Encode a mission_write_partial_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_write_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ - return mavlink_msg_mission_write_partial_list_pack(system_id, component_id, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index); -} - -/** - * @brief Encode a mission_write_partial_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_write_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ - return mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, chan, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index); -} - -/** - * @brief Send a mission_write_partial_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - mavlink_mission_write_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - 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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#endif -} - -/** - * @brief Send a mission_write_partial_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_write_partial_list_send_struct(mavlink_channel_t chan, const mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_write_partial_list_send(chan, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)mission_write_partial_list, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_write_partial_list_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - mavlink_mission_write_partial_list_t *packet = (mavlink_mission_write_partial_list_t *)msgbuf; - packet->start_index = start_index; - packet->end_index = end_index; - 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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_WRITE_PARTIAL_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_write_partial_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from mission_write_partial_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start_index from mission_write_partial_list message - * - * @return Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - */ -static inline int16_t mavlink_msg_mission_write_partial_list_get_start_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field end_index from mission_write_partial_list message - * - * @return End index, equal or greater than start index. - */ -static inline int16_t mavlink_msg_mission_write_partial_list_get_end_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Decode a mission_write_partial_list message into a struct - * - * @param msg The message to decode - * @param mission_write_partial_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_write_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_write_partial_list->start_index = mavlink_msg_mission_write_partial_list_get_start_index(msg); - mission_write_partial_list->end_index = mavlink_msg_mission_write_partial_list_get_end_index(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN; - memset(mission_write_partial_list, 0, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); - memcpy(mission_write_partial_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h b/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h deleted file mode 100644 index 99cf094..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE NAMED_VALUE_FLOAT PACKING - -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 - -MAVPACKED( -typedef struct __mavlink_named_value_float_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float value; /*< Floating point value*/ - char name[10]; /*< Name of the debug variable*/ -}) mavlink_named_value_float_t; - -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN 18 -#define MAVLINK_MSG_ID_251_LEN 18 -#define MAVLINK_MSG_ID_251_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ - 251, \ - "NAMED_VALUE_FLOAT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ - "NAMED_VALUE_FLOAT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ - } \ -} -#endif - -/** - * @brief Pack a named_value_float 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_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, const char *name, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -} - -/** - * @brief Pack a named_value_float message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,const char *name,float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -} - -/** - * @brief Encode a named_value_float struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param named_value_float C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) -{ - return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); -} - -/** - * @brief Encode a named_value_float struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param named_value_float C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_float_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) -{ - return mavlink_msg_named_value_float_pack_chan(system_id, component_id, chan, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); -} - -/** - * @brief Send a named_value_float message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#endif -} - -/** - * @brief Send a named_value_float message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_named_value_float_send_struct(mavlink_channel_t chan, const mavlink_named_value_float_t* named_value_float) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_named_value_float_send(chan, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)named_value_float, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_named_value_float_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#else - mavlink_named_value_float_t *packet = (mavlink_named_value_float_t *)msgbuf; - 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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE NAMED_VALUE_FLOAT UNPACKING - - -/** - * @brief Get field time_boot_ms from named_value_float message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field name from named_value_float message - * - * @return Name of the debug variable - */ -static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 8); -} - -/** - * @brief Get field value from named_value_float message - * - * @return Floating point value - */ -static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Decode a named_value_float message into a struct - * - * @param msg The message to decode - * @param named_value_float C-struct to decode the message contents into - */ -static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - named_value_float->time_boot_ms = mavlink_msg_named_value_float_get_time_boot_ms(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN? msg->len : MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN; - memset(named_value_float, 0, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); - memcpy(named_value_float, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h b/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h deleted file mode 100644 index b0b3b96..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE NAMED_VALUE_INT PACKING - -#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252 - -MAVPACKED( -typedef struct __mavlink_named_value_int_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int32_t value; /*< Signed integer value*/ - char name[10]; /*< Name of the debug variable*/ -}) mavlink_named_value_int_t; - -#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 -#define MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN 18 -#define MAVLINK_MSG_ID_252_LEN 18 -#define MAVLINK_MSG_ID_252_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ - 252, \ - "NAMED_VALUE_INT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ - "NAMED_VALUE_INT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ - } \ -} -#endif - -/** - * @brief Pack a named_value_int 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_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, const char *name, int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -} - -/** - * @brief Pack a named_value_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,const char *name,int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -} - -/** - * @brief Encode a named_value_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param named_value_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) -{ - return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); -} - -/** - * @brief Encode a named_value_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param named_value_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) -{ - return mavlink_msg_named_value_int_pack_chan(system_id, component_id, chan, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); -} - -/** - * @brief Send a named_value_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#endif -} - -/** - * @brief Send a named_value_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_named_value_int_send_struct(mavlink_channel_t chan, const mavlink_named_value_int_t* named_value_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_named_value_int_send(chan, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)named_value_int, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_named_value_int_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#else - mavlink_named_value_int_t *packet = (mavlink_named_value_int_t *)msgbuf; - 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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE NAMED_VALUE_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from named_value_int message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field name from named_value_int message - * - * @return Name of the debug variable - */ -static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 8); -} - -/** - * @brief Get field value from named_value_int message - * - * @return Signed integer value - */ -static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Decode a named_value_int message into a struct - * - * @param msg The message to decode - * @param named_value_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - named_value_int->time_boot_ms = mavlink_msg_named_value_int_get_time_boot_ms(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN? msg->len : MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN; - memset(named_value_int, 0, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); - memcpy(named_value_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h b/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h deleted file mode 100644 index 5f2d40f..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE NAV_CONTROLLER_OUTPUT PACKING - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 - -MAVPACKED( -typedef struct __mavlink_nav_controller_output_t { - float nav_roll; /*< Current desired roll in degrees*/ - float nav_pitch; /*< Current desired pitch in degrees*/ - float alt_error; /*< Current altitude error in meters*/ - float aspd_error; /*< Current airspeed error in meters/second*/ - float xtrack_error; /*< Current crosstrack error on x-y plane in meters*/ - int16_t nav_bearing; /*< Current desired heading in degrees*/ - int16_t target_bearing; /*< Bearing to current MISSION/target in degrees*/ - uint16_t wp_dist; /*< Distance to active MISSION in meters*/ -}) mavlink_nav_controller_output_t; - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN 26 -#define MAVLINK_MSG_ID_62_LEN 26 -#define MAVLINK_MSG_ID_62_MIN_LEN 26 - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183 -#define MAVLINK_MSG_ID_62_CRC 183 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ - 62, \ - "NAV_CONTROLLER_OUTPUT", \ - 8, \ - { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ - { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ - { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ - { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ - { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ - { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ - { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ - { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ - "NAV_CONTROLLER_OUTPUT", \ - 8, \ - { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ - { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ - { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ - { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ - { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ - { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ - { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ - { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ - } \ -} -#endif - -/** - * @brief Pack a nav_controller_output 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 nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - - 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; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - packet.target_bearing = target_bearing; - packet.wp_dist = wp_dist; - - 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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -} - -/** - * @brief Pack a nav_controller_output message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - - 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; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - packet.target_bearing = target_bearing; - packet.wp_dist = wp_dist; - - 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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -} - -/** - * @brief Encode a nav_controller_output struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param nav_controller_output C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) -{ - return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); -} - -/** - * @brief Encode a nav_controller_output struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param nav_controller_output C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_nav_controller_output_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) -{ - return mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, chan, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); -} - -/** - * @brief Send a nav_controller_output message - * @param chan MAVLink channel to send the message - * - * @param nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - mavlink_nav_controller_output_t packet; - packet.nav_roll = nav_roll; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - 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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#endif -} - -/** - * @brief Send a nav_controller_output message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_nav_controller_output_send_struct(mavlink_channel_t chan, const mavlink_nav_controller_output_t* nav_controller_output) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_nav_controller_output_send(chan, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)nav_controller_output, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_float(buf, 0, nav_roll); - _mav_put_float(buf, 4, nav_pitch); - _mav_put_float(buf, 8, alt_error); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - mavlink_nav_controller_output_t *packet = (mavlink_nav_controller_output_t *)msgbuf; - packet->nav_roll = nav_roll; - packet->nav_pitch = nav_pitch; - packet->alt_error = alt_error; - packet->aspd_error = aspd_error; - packet->xtrack_error = xtrack_error; - packet->nav_bearing = nav_bearing; - 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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING - - -/** - * @brief Get field nav_roll from nav_controller_output message - * - * @return Current desired roll in degrees - */ -static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field nav_pitch from nav_controller_output message - * - * @return Current desired pitch in degrees - */ -static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field nav_bearing from nav_controller_output message - * - * @return Current desired heading in degrees - */ -static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field target_bearing from nav_controller_output message - * - * @return Bearing to current MISSION/target in degrees - */ -static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field wp_dist from nav_controller_output message - * - * @return Distance to active MISSION in meters - */ -static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field alt_error from nav_controller_output message - * - * @return Current altitude error in meters - */ -static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field aspd_error from nav_controller_output message - * - * @return Current airspeed error in meters/second - */ -static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field xtrack_error from nav_controller_output message - * - * @return Current crosstrack error on x-y plane in meters - */ -static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a nav_controller_output message into a struct - * - * @param msg The message to decode - * @param nav_controller_output C-struct to decode the message contents into - */ -static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg); - nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg); - nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg); - nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg); - nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg); - nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN? msg->len : MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN; - memset(nav_controller_output, 0, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); - memcpy(nav_controller_output, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h b/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h deleted file mode 100644 index 56b9a3c..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE OPTICAL_FLOW PACKING - -#define MAVLINK_MSG_ID_OPTICAL_FLOW 100 - -MAVPACKED( -typedef struct __mavlink_optical_flow_t { - uint64_t time_usec; /*< Timestamp (UNIX)*/ - float flow_comp_m_x; /*< Flow in meters in x-sensor direction, angular-speed compensated*/ - float flow_comp_m_y; /*< Flow in meters in y-sensor direction, angular-speed compensated*/ - float ground_distance; /*< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance*/ - int16_t flow_x; /*< Flow in pixels * 10 in x-sensor direction (dezi-pixels)*/ - int16_t flow_y; /*< Flow in pixels * 10 in y-sensor direction (dezi-pixels)*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: bad, 255: maximum quality*/ -}) mavlink_optical_flow_t; - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 -#define MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN 26 -#define MAVLINK_MSG_ID_100_LEN 26 -#define MAVLINK_MSG_ID_100_MIN_LEN 26 - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 -#define MAVLINK_MSG_ID_100_CRC 175 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ - 100, \ - "OPTICAL_FLOW", \ - 8, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ - { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ - { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ - { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ - { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ - { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ - "OPTICAL_FLOW", \ - 8, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ - { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ - { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ - { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ - { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ - { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ - } \ -} -#endif - -/** - * @brief Pack a optical_flow 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 (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - - 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, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -} - -/** - * @brief Pack a optical_flow message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - - 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, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -} - -/** - * @brief Encode a optical_flow struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) -{ - return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance); -} - -/** - * @brief Encode a optical_flow struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) -{ - return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance); -} - -/** - * @brief Send a optical_flow message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _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, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#endif -} - -/** - * @brief Send a optical_flow message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_optical_flow_send_struct(mavlink_channel_t chan, const mavlink_optical_flow_t* optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_optical_flow_send(chan, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)optical_flow, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _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, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - mavlink_optical_flow_t *packet = (mavlink_optical_flow_t *)msgbuf; - packet->time_usec = time_usec; - packet->flow_comp_m_x = flow_comp_m_x; - packet->flow_comp_m_y = flow_comp_m_y; - packet->ground_distance = ground_distance; - packet->flow_x = flow_x; - packet->flow_y = flow_y; - packet->sensor_id = sensor_id; - packet->quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPTICAL_FLOW UNPACKING - - -/** - * @brief Get field time_usec from optical_flow message - * - * @return Timestamp (UNIX) - */ -static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from optical_flow message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field flow_x from optical_flow message - * - * @return Flow in pixels * 10 in x-sensor direction (dezi-pixels) - */ -static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field flow_y from optical_flow message - * - * @return Flow in pixels * 10 in y-sensor direction (dezi-pixels) - */ -static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field flow_comp_m_x from optical_flow message - * - * @return Flow in meters in x-sensor direction, angular-speed compensated - */ -static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field flow_comp_m_y from optical_flow message - * - * @return Flow in meters in y-sensor direction, angular-speed compensated - */ -static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field quality from optical_flow message - * - * @return Optical flow quality / confidence. 0: bad, 255: maximum quality - */ -static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field ground_distance from optical_flow message - * - * @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - */ -static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a optical_flow message into a struct - * - * @param msg The message to decode - * @param optical_flow C-struct to decode the message contents into - */ -static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg); - optical_flow->flow_comp_m_x = mavlink_msg_optical_flow_get_flow_comp_m_x(msg); - optical_flow->flow_comp_m_y = mavlink_msg_optical_flow_get_flow_comp_m_y(msg); - optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg); - optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg); - optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg); - optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg); - optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPTICAL_FLOW_LEN? msg->len : MAVLINK_MSG_ID_OPTICAL_FLOW_LEN; - memset(optical_flow, 0, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); - memcpy(optical_flow, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_optical_flow_rad.h b/include/mavlink/v1.0/common/mavlink_msg_optical_flow_rad.h deleted file mode 100644 index c4326eb..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_optical_flow_rad.h +++ /dev/null @@ -1,488 +0,0 @@ -#pragma once -// MESSAGE OPTICAL_FLOW_RAD PACKING - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD 106 - -MAVPACKED( -typedef struct __mavlink_optical_flow_rad_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ - float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ - float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ - float integrated_xgyro; /*< RH rotation around X axis (rad)*/ - float integrated_ygyro; /*< RH rotation around Y axis (rad)*/ - float integrated_zgyro; /*< RH rotation around Z axis (rad)*/ - uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/ - float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/ - int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ -}) mavlink_optical_flow_rad_t; - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN 44 -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN 44 -#define MAVLINK_MSG_ID_106_LEN 44 -#define MAVLINK_MSG_ID_106_MIN_LEN 44 - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC 138 -#define MAVLINK_MSG_ID_106_CRC 138 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD { \ - 106, \ - "OPTICAL_FLOW_RAD", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD { \ - "OPTICAL_FLOW_RAD", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ - } \ -} -#endif - -/** - * @brief Pack a optical_flow_rad 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 sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_rad_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#else - mavlink_optical_flow_rad_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -} - -/** - * @brief Pack a optical_flow_rad message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_rad_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_id,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#else - mavlink_optical_flow_rad_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -} - -/** - * @brief Encode a optical_flow_rad struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param optical_flow_rad C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_rad_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad) -{ - return mavlink_msg_optical_flow_rad_pack(system_id, component_id, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); -} - -/** - * @brief Encode a optical_flow_rad struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param optical_flow_rad C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_rad_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad) -{ - return mavlink_msg_optical_flow_rad_pack_chan(system_id, component_id, chan, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); -} - -/** - * @brief Send a optical_flow_rad message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_optical_flow_rad_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#else - mavlink_optical_flow_rad_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#endif -} - -/** - * @brief Send a optical_flow_rad message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_optical_flow_rad_send_struct(mavlink_channel_t chan, const mavlink_optical_flow_rad_t* optical_flow_rad) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_optical_flow_rad_send(chan, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)optical_flow_rad, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_optical_flow_rad_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#else - mavlink_optical_flow_rad_t *packet = (mavlink_optical_flow_rad_t *)msgbuf; - packet->time_usec = time_usec; - packet->integration_time_us = integration_time_us; - packet->integrated_x = integrated_x; - packet->integrated_y = integrated_y; - packet->integrated_xgyro = integrated_xgyro; - packet->integrated_ygyro = integrated_ygyro; - packet->integrated_zgyro = integrated_zgyro; - packet->time_delta_distance_us = time_delta_distance_us; - packet->distance = distance; - packet->temperature = temperature; - packet->sensor_id = sensor_id; - packet->quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPTICAL_FLOW_RAD UNPACKING - - -/** - * @brief Get field time_usec from optical_flow_rad message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_optical_flow_rad_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from optical_flow_rad message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_optical_flow_rad_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field integration_time_us from optical_flow_rad message - * - * @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - */ -static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field integrated_x from optical_flow_rad message - * - * @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field integrated_y from optical_flow_rad message - * - * @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field integrated_xgyro from optical_flow_rad message - * - * @return RH rotation around X axis (rad) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field integrated_ygyro from optical_flow_rad message - * - * @return RH rotation around Y axis (rad) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field integrated_zgyro from optical_flow_rad message - * - * @return RH rotation around Z axis (rad) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field temperature from optical_flow_rad message - * - * @return Temperature * 100 in centi-degrees Celsius - */ -static inline int16_t mavlink_msg_optical_flow_rad_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 40); -} - -/** - * @brief Get field quality from optical_flow_rad message - * - * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - */ -static inline uint8_t mavlink_msg_optical_flow_rad_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 43); -} - -/** - * @brief Get field time_delta_distance_us from optical_flow_rad message - * - * @return Time in microseconds since the distance was sampled. - */ -static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 32); -} - -/** - * @brief Get field distance from optical_flow_rad message - * - * @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -static inline float mavlink_msg_optical_flow_rad_get_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a optical_flow_rad message into a struct - * - * @param msg The message to decode - * @param optical_flow_rad C-struct to decode the message contents into - */ -static inline void mavlink_msg_optical_flow_rad_decode(const mavlink_message_t* msg, mavlink_optical_flow_rad_t* optical_flow_rad) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - optical_flow_rad->time_usec = mavlink_msg_optical_flow_rad_get_time_usec(msg); - optical_flow_rad->integration_time_us = mavlink_msg_optical_flow_rad_get_integration_time_us(msg); - optical_flow_rad->integrated_x = mavlink_msg_optical_flow_rad_get_integrated_x(msg); - optical_flow_rad->integrated_y = mavlink_msg_optical_flow_rad_get_integrated_y(msg); - optical_flow_rad->integrated_xgyro = mavlink_msg_optical_flow_rad_get_integrated_xgyro(msg); - optical_flow_rad->integrated_ygyro = mavlink_msg_optical_flow_rad_get_integrated_ygyro(msg); - optical_flow_rad->integrated_zgyro = mavlink_msg_optical_flow_rad_get_integrated_zgyro(msg); - optical_flow_rad->time_delta_distance_us = mavlink_msg_optical_flow_rad_get_time_delta_distance_us(msg); - optical_flow_rad->distance = mavlink_msg_optical_flow_rad_get_distance(msg); - optical_flow_rad->temperature = mavlink_msg_optical_flow_rad_get_temperature(msg); - optical_flow_rad->sensor_id = mavlink_msg_optical_flow_rad_get_sensor_id(msg); - optical_flow_rad->quality = mavlink_msg_optical_flow_rad_get_quality(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN? msg->len : MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN; - memset(optical_flow_rad, 0, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); - memcpy(optical_flow_rad, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_param_map_rc.h b/include/mavlink/v1.0/common/mavlink_msg_param_map_rc.h deleted file mode 100644 index 5b64b7f..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_param_map_rc.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE PARAM_MAP_RC PACKING - -#define MAVLINK_MSG_ID_PARAM_MAP_RC 50 - -MAVPACKED( -typedef struct __mavlink_param_map_rc_t { - float param_value0; /*< Initial parameter value*/ - float scale; /*< Scale, maps the RC range [-1, 1] to a parameter value*/ - float param_value_min; /*< Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)*/ - float param_value_max; /*< Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)*/ - int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t parameter_rc_channel_index; /*< Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.*/ -}) mavlink_param_map_rc_t; - -#define MAVLINK_MSG_ID_PARAM_MAP_RC_LEN 37 -#define MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN 37 -#define MAVLINK_MSG_ID_50_LEN 37 -#define MAVLINK_MSG_ID_50_MIN_LEN 37 - -#define MAVLINK_MSG_ID_PARAM_MAP_RC_CRC 78 -#define MAVLINK_MSG_ID_50_CRC 78 - -#define MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \ - 50, \ - "PARAM_MAP_RC", \ - 9, \ - { { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ - { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \ - { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \ - { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ - { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \ - "PARAM_MAP_RC", \ - 9, \ - { { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ - { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \ - { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \ - { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ - { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_map_rc message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_map_rc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#else - mavlink_param_map_rc_t packet; - packet.param_value0 = param_value0; - packet.scale = scale; - packet.param_value_min = param_value_min; - packet.param_value_max = param_value_max; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -} - -/** - * @brief Pack a param_map_rc message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_map_rc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index,uint8_t parameter_rc_channel_index,float param_value0,float scale,float param_value_min,float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#else - mavlink_param_map_rc_t packet; - packet.param_value0 = param_value0; - packet.scale = scale; - packet.param_value_min = param_value_min; - packet.param_value_max = param_value_max; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -} - -/** - * @brief Encode a param_map_rc struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_map_rc C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_map_rc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc) -{ - return mavlink_msg_param_map_rc_pack(system_id, component_id, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); -} - -/** - * @brief Encode a param_map_rc struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_map_rc C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_map_rc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc) -{ - return mavlink_msg_param_map_rc_pack_chan(system_id, component_id, chan, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); -} - -/** - * @brief Send a param_map_rc message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_map_rc_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#else - mavlink_param_map_rc_t packet; - packet.param_value0 = param_value0; - packet.scale = scale; - packet.param_value_min = param_value_min; - packet.param_value_max = param_value_max; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)&packet, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#endif -} - -/** - * @brief Send a param_map_rc message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_map_rc_send_struct(mavlink_channel_t chan, const mavlink_param_map_rc_t* param_map_rc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_map_rc_send(chan, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)param_map_rc, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_MAP_RC_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_map_rc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#else - mavlink_param_map_rc_t *packet = (mavlink_param_map_rc_t *)msgbuf; - packet->param_value0 = param_value0; - packet->scale = scale; - packet->param_value_min = param_value_min; - packet->param_value_max = param_value_max; - packet->param_index = param_index; - packet->target_system = target_system; - packet->target_component = target_component; - packet->parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)packet, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_MAP_RC UNPACKING - - -/** - * @brief Get field target_system from param_map_rc message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_map_rc_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field target_component from param_map_rc message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_map_rc_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 19); -} - -/** - * @brief Get field param_id from param_map_rc message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_map_rc_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 20); -} - -/** - * @brief Get field param_index from param_map_rc message - * - * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - */ -static inline int16_t mavlink_msg_param_map_rc_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field parameter_rc_channel_index from param_map_rc message - * - * @return Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - */ -static inline uint8_t mavlink_msg_param_map_rc_get_parameter_rc_channel_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field param_value0 from param_map_rc message - * - * @return Initial parameter value - */ -static inline float mavlink_msg_param_map_rc_get_param_value0(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field scale from param_map_rc message - * - * @return Scale, maps the RC range [-1, 1] to a parameter value - */ -static inline float mavlink_msg_param_map_rc_get_scale(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param_value_min from param_map_rc message - * - * @return Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - */ -static inline float mavlink_msg_param_map_rc_get_param_value_min(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param_value_max from param_map_rc message - * - * @return Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - */ -static inline float mavlink_msg_param_map_rc_get_param_value_max(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a param_map_rc message into a struct - * - * @param msg The message to decode - * @param param_map_rc C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_map_rc_decode(const mavlink_message_t* msg, mavlink_param_map_rc_t* param_map_rc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_map_rc->param_value0 = mavlink_msg_param_map_rc_get_param_value0(msg); - param_map_rc->scale = mavlink_msg_param_map_rc_get_scale(msg); - param_map_rc->param_value_min = mavlink_msg_param_map_rc_get_param_value_min(msg); - param_map_rc->param_value_max = mavlink_msg_param_map_rc_get_param_value_max(msg); - param_map_rc->param_index = mavlink_msg_param_map_rc_get_param_index(msg); - param_map_rc->target_system = mavlink_msg_param_map_rc_get_target_system(msg); - param_map_rc->target_component = mavlink_msg_param_map_rc_get_target_component(msg); - mavlink_msg_param_map_rc_get_param_id(msg, param_map_rc->param_id); - param_map_rc->parameter_rc_channel_index = mavlink_msg_param_map_rc_get_parameter_rc_channel_index(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_MAP_RC_LEN? msg->len : MAVLINK_MSG_ID_PARAM_MAP_RC_LEN; - memset(param_map_rc, 0, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); - memcpy(param_map_rc, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h b/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h deleted file mode 100644 index 2c5da24..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE PARAM_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 - -MAVPACKED( -typedef struct __mavlink_param_request_list_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_param_request_list_t; - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN 2 -#define MAVLINK_MSG_ID_21_LEN 2 -#define MAVLINK_MSG_ID_21_MIN_LEN 2 - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC 159 -#define MAVLINK_MSG_ID_21_CRC 159 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ - 21, \ - "PARAM_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ - "PARAM_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -} - -/** - * @brief Pack a param_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -} - -/** - * @brief Encode a param_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) -{ - return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component); -} - -/** - * @brief Encode a param_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) -{ - return mavlink_msg_param_request_list_pack_chan(system_id, component_id, chan, msg, param_request_list->target_system, param_request_list->target_component); -} - -/** - * @brief Send a param_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#endif -} - -/** - * @brief Send a param_request_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_request_list_send_struct(mavlink_channel_t chan, const mavlink_param_request_list_t* param_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_request_list_send(chan, param_request_list->target_system, param_request_list->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)param_request_list, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#else - mavlink_param_request_list_t *packet = (mavlink_param_request_list_t *)msgbuf; - 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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from param_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from param_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a param_request_list message into a struct - * - * @param msg The message to decode - * @param param_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN; - memset(param_request_list, 0, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); - memcpy(param_request_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h b/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h deleted file mode 100644 index 5381596..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE PARAM_REQUEST_READ PACKING - -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 - -MAVPACKED( -typedef struct __mavlink_param_request_read_t { - int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ -}) mavlink_param_request_read_t; - -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN 20 -#define MAVLINK_MSG_ID_20_LEN 20 -#define MAVLINK_MSG_ID_20_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ - 20, \ - "PARAM_REQUEST_READ", \ - 4, \ - { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ - "PARAM_REQUEST_READ", \ - 4, \ - { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_request_read message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, 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, 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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -} - -/** - * @brief Pack a param_request_read message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, 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, 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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -} - -/** - * @brief Encode a param_request_read struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_request_read C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) -{ - return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); -} - -/** - * @brief Encode a param_request_read struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_request_read C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) -{ - return mavlink_msg_param_request_read_pack_chan(system_id, component_id, chan, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); -} - -/** - * @brief Send a param_request_read message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#endif -} - -/** - * @brief Send a param_request_read message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_request_read_send_struct(mavlink_channel_t chan, const mavlink_param_request_read_t* param_request_read) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_request_read_send(chan, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)param_request_read, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_request_read_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#else - mavlink_param_request_read_t *packet = (mavlink_param_request_read_t *)msgbuf; - 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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_REQUEST_READ UNPACKING - - -/** - * @brief Get field target_system from param_request_read message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from param_request_read message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field param_id from param_request_read message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 4); -} - -/** - * @brief Get field param_index from param_request_read message - * - * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - */ -static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Decode a param_request_read message into a struct - * - * @param msg The message to decode - * @param param_request_read C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg); - param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN? msg->len : MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN; - memset(param_request_read, 0, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); - memcpy(param_request_read, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_param_set.h b/include/mavlink/v1.0/common/mavlink_msg_param_set.h deleted file mode 100644 index cc73109..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_param_set.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE PARAM_SET PACKING - -#define MAVLINK_MSG_ID_PARAM_SET 23 - -MAVPACKED( -typedef struct __mavlink_param_set_t { - float param_value; /*< Onboard parameter value*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/ -}) mavlink_param_set_t; - -#define MAVLINK_MSG_ID_PARAM_SET_LEN 23 -#define MAVLINK_MSG_ID_PARAM_SET_MIN_LEN 23 -#define MAVLINK_MSG_ID_23_LEN 23 -#define MAVLINK_MSG_ID_23_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_SET { \ - 23, \ - "PARAM_SET", \ - 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_SET { \ - "PARAM_SET", \ - 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_set message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PARAM_SET_LEN); -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - 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, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_SET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -} - -/** - * @brief Pack a param_set message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PARAM_SET_LEN); -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - 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, 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, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -} - -/** - * @brief Encode a param_set struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set) -{ - return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); -} - -/** - * @brief Encode a param_set struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_set_t* param_set) -{ - return mavlink_msg_param_set_pack_chan(system_id, component_id, chan, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); -} - -/** - * @brief Send a param_set message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - 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, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#endif -} - -/** - * @brief Send a param_set message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_set_send_struct(mavlink_channel_t chan, const mavlink_param_set_t* param_set) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_set_send(chan, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)param_set, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 22, param_type); - _mav_put_char_array(buf, 6, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - mavlink_param_set_t *packet = (mavlink_param_set_t *)msgbuf; - packet->param_value = param_value; - packet->target_system = target_system; - 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, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_SET UNPACKING - - -/** - * @brief Get field target_system from param_set message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from param_set message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field param_id from param_set message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 6); -} - -/** - * @brief Get field param_value from param_set message - * - * @return Onboard parameter value - */ -static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param_type from param_set message - * - * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - */ -static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Decode a param_set message into a struct - * - * @param msg The message to decode - * @param param_set C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_set->param_value = mavlink_msg_param_set_get_param_value(msg); - param_set->target_system = mavlink_msg_param_set_get_target_system(msg); - param_set->target_component = mavlink_msg_param_set_get_target_component(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_SET_LEN? msg->len : MAVLINK_MSG_ID_PARAM_SET_LEN; - memset(param_set, 0, MAVLINK_MSG_ID_PARAM_SET_LEN); - memcpy(param_set, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_param_value.h b/include/mavlink/v1.0/common/mavlink_msg_param_value.h deleted file mode 100644 index e2cb891..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_param_value.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE PARAM_VALUE PACKING - -#define MAVLINK_MSG_ID_PARAM_VALUE 22 - -MAVPACKED( -typedef struct __mavlink_param_value_t { - float param_value; /*< Onboard parameter value*/ - uint16_t param_count; /*< Total number of onboard parameters*/ - uint16_t param_index; /*< Index of this onboard parameter*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/ -}) mavlink_param_value_t; - -#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 -#define MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN 25 -#define MAVLINK_MSG_ID_22_LEN 25 -#define MAVLINK_MSG_ID_22_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ - 22, \ - "PARAM_VALUE", \ - 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ - { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ - { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ - "PARAM_VALUE", \ - 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ - { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ - { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_value 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 param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - 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, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -} - -/** - * @brief Pack a param_value message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - 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, 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, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -} - -/** - * @brief Encode a param_value struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_value C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value) -{ - return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); -} - -/** - * @brief Encode a param_value struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_value C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_value_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_value_t* param_value) -{ - return mavlink_msg_param_value_pack_chan(system_id, component_id, chan, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); -} - -/** - * @brief Send a param_value message - * @param chan MAVLink channel to send the message - * - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - 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, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#endif -} - -/** - * @brief Send a param_value message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_value_send_struct(mavlink_channel_t chan, const mavlink_param_value_t* param_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_value_send(chan, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)param_value, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_VALUE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_value_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - mavlink_param_value_t *packet = (mavlink_param_value_t *)msgbuf; - packet->param_value = param_value; - packet->param_count = param_count; - 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, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_VALUE UNPACKING - - -/** - * @brief Get field param_id from param_value message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 8); -} - -/** - * @brief Get field param_value from param_value message - * - * @return Onboard parameter value - */ -static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param_type from param_value message - * - * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - */ -static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field param_count from param_value message - * - * @return Total number of onboard parameters - */ -static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field param_index from param_value message - * - * @return Index of this onboard parameter - */ -static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Decode a param_value message into a struct - * - * @param msg The message to decode - * @param param_value C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_value->param_value = mavlink_msg_param_value_get_param_value(msg); - param_value->param_count = mavlink_msg_param_value_get_param_count(msg); - param_value->param_index = mavlink_msg_param_value_get_param_index(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 - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_VALUE_LEN? msg->len : MAVLINK_MSG_ID_PARAM_VALUE_LEN; - memset(param_value, 0, MAVLINK_MSG_ID_PARAM_VALUE_LEN); - memcpy(param_value, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_ping.h b/include/mavlink/v1.0/common/mavlink_msg_ping.h deleted file mode 100644 index 1e18bc6..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_ping.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE PING PACKING - -#define MAVLINK_MSG_ID_PING 4 - -MAVPACKED( -typedef struct __mavlink_ping_t { - uint64_t time_usec; /*< Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)*/ - uint32_t seq; /*< PING sequence*/ - uint8_t target_system; /*< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system*/ - uint8_t target_component; /*< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system*/ -}) mavlink_ping_t; - -#define MAVLINK_MSG_ID_PING_LEN 14 -#define MAVLINK_MSG_ID_PING_MIN_LEN 14 -#define MAVLINK_MSG_ID_4_LEN 14 -#define MAVLINK_MSG_ID_4_MIN_LEN 14 - -#define MAVLINK_MSG_ID_PING_CRC 237 -#define MAVLINK_MSG_ID_4_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PING { \ - 4, \ - "PING", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PING { \ - "PING", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a ping 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 Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PING_LEN); -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -} - -/** - * @brief Pack a ping message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PING_LEN); -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -} - -/** - * @brief Encode a ping struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param ping C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping) -{ - return mavlink_msg_ping_pack(system_id, component_id, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); -} - -/** - * @brief Encode a ping struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ping C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ping_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_t* ping) -{ - return mavlink_msg_ping_pack_chan(system_id, component_id, chan, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); -} - -/** - * @brief Send a ping message - * @param chan MAVLink channel to send the message - * - * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#endif -} - -/** - * @brief Send a ping message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_ping_send_struct(mavlink_channel_t chan, const mavlink_ping_t* ping) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_ping_send(chan, ping->time_usec, ping->seq, ping->target_system, ping->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)ping, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PING_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_ping_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - mavlink_ping_t *packet = (mavlink_ping_t *)msgbuf; - packet->time_usec = time_usec; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PING UNPACKING - - -/** - * @brief Get field time_usec from ping message - * - * @return Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - */ -static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field seq from ping message - * - * @return PING sequence - */ -static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field target_system from ping message - * - * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - */ -static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field target_component from ping message - * - * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - */ -static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Decode a ping message into a struct - * - * @param msg The message to decode - * @param ping C-struct to decode the message contents into - */ -static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - ping->time_usec = mavlink_msg_ping_get_time_usec(msg); - ping->seq = mavlink_msg_ping_get_seq(msg); - ping->target_system = mavlink_msg_ping_get_target_system(msg); - ping->target_component = mavlink_msg_ping_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PING_LEN? msg->len : MAVLINK_MSG_ID_PING_LEN; - memset(ping, 0, MAVLINK_MSG_ID_PING_LEN); - memcpy(ping, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_position_target_global_int.h b/include/mavlink/v1.0/common/mavlink_msg_position_target_global_int.h deleted file mode 100644 index 160a5fa..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_position_target_global_int.h +++ /dev/null @@ -1,538 +0,0 @@ -#pragma once -// MESSAGE POSITION_TARGET_GLOBAL_INT PACKING - -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87 - -MAVPACKED( -typedef struct __mavlink_position_target_global_int_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ - int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/ - int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/ - float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ -}) mavlink_position_target_global_int_t; - -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51 -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN 51 -#define MAVLINK_MSG_ID_87_LEN 51 -#define MAVLINK_MSG_ID_87_MIN_LEN 51 - -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150 -#define MAVLINK_MSG_ID_87_CRC 150 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \ - 87, \ - "POSITION_TARGET_GLOBAL_INT", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \ - "POSITION_TARGET_GLOBAL_INT", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a position_target_global_int 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_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Pack a position_target_global_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Encode a position_target_global_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int) -{ - return mavlink_msg_position_target_global_int_pack(system_id, component_id, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); -} - -/** - * @brief Encode a position_target_global_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int) -{ - return mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, chan, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); -} - -/** - * @brief Send a position_target_global_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -/** - * @brief Send a position_target_global_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_position_target_global_int_send_struct(mavlink_channel_t chan, const mavlink_position_target_global_int_t* position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_position_target_global_int_send(chan, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)position_target_global_int, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_position_target_global_int_t *packet = (mavlink_position_target_global_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->lat_int = lat_int; - packet->lon_int = lon_int; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE POSITION_TARGET_GLOBAL_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from position_target_global_int message - * - * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - */ -static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field coordinate_frame from position_target_global_int message - * - * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - */ -static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field type_mask from position_target_global_int message - * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - */ -static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field lat_int from position_target_global_int message - * - * @return X Position in WGS84 frame in 1e7 * meters - */ -static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon_int from position_target_global_int message - * - * @return Y Position in WGS84 frame in 1e7 * meters - */ -static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt from position_target_global_int message - * - * @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - */ -static inline float mavlink_msg_position_target_global_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from position_target_global_int message - * - * @return X velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_global_int_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from position_target_global_int message - * - * @return Y velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_global_int_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from position_target_global_int message - * - * @return Z velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_global_int_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from position_target_global_int message - * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_global_int_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from position_target_global_int message - * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_global_int_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from position_target_global_int message - * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from position_target_global_int message - * - * @return yaw setpoint in rad - */ -static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from position_target_global_int message - * - * @return yaw rate setpoint in rad/s - */ -static inline float mavlink_msg_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a position_target_global_int message into a struct - * - * @param msg The message to decode - * @param position_target_global_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_position_target_global_int_t* position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - position_target_global_int->time_boot_ms = mavlink_msg_position_target_global_int_get_time_boot_ms(msg); - position_target_global_int->lat_int = mavlink_msg_position_target_global_int_get_lat_int(msg); - position_target_global_int->lon_int = mavlink_msg_position_target_global_int_get_lon_int(msg); - position_target_global_int->alt = mavlink_msg_position_target_global_int_get_alt(msg); - position_target_global_int->vx = mavlink_msg_position_target_global_int_get_vx(msg); - position_target_global_int->vy = mavlink_msg_position_target_global_int_get_vy(msg); - position_target_global_int->vz = mavlink_msg_position_target_global_int_get_vz(msg); - position_target_global_int->afx = mavlink_msg_position_target_global_int_get_afx(msg); - position_target_global_int->afy = mavlink_msg_position_target_global_int_get_afy(msg); - position_target_global_int->afz = mavlink_msg_position_target_global_int_get_afz(msg); - position_target_global_int->yaw = mavlink_msg_position_target_global_int_get_yaw(msg); - position_target_global_int->yaw_rate = mavlink_msg_position_target_global_int_get_yaw_rate(msg); - position_target_global_int->type_mask = mavlink_msg_position_target_global_int_get_type_mask(msg); - position_target_global_int->coordinate_frame = mavlink_msg_position_target_global_int_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN? msg->len : MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN; - memset(position_target_global_int, 0, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); - memcpy(position_target_global_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_position_target_local_ned.h b/include/mavlink/v1.0/common/mavlink_msg_position_target_local_ned.h deleted file mode 100644 index 3464e9a..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_position_target_local_ned.h +++ /dev/null @@ -1,538 +0,0 @@ -#pragma once -// MESSAGE POSITION_TARGET_LOCAL_NED PACKING - -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED 85 - -MAVPACKED( -typedef struct __mavlink_position_target_local_ned_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float x; /*< X Position in NED frame in meters*/ - float y; /*< Y Position in NED frame in meters*/ - float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ -}) mavlink_position_target_local_ned_t; - -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51 -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN 51 -#define MAVLINK_MSG_ID_85_LEN 51 -#define MAVLINK_MSG_ID_85_MIN_LEN 51 - -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 140 -#define MAVLINK_MSG_ID_85_CRC 140 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \ - 85, \ - "POSITION_TARGET_LOCAL_NED", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \ - "POSITION_TARGET_LOCAL_NED", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a position_target_local_ned 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_boot_ms Timestamp in milliseconds since system boot - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Pack a position_target_local_ned message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Encode a position_target_local_ned struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned) -{ - return mavlink_msg_position_target_local_ned_pack(system_id, component_id, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); -} - -/** - * @brief Encode a position_target_local_ned struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned) -{ - return mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); -} - -/** - * @brief Send a position_target_local_ned message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -/** - * @brief Send a position_target_local_ned message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_position_target_local_ned_send_struct(mavlink_channel_t chan, const mavlink_position_target_local_ned_t* position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_position_target_local_ned_send(chan, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)position_target_local_ned, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_position_target_local_ned_t *packet = (mavlink_position_target_local_ned_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE POSITION_TARGET_LOCAL_NED UNPACKING - - -/** - * @brief Get field time_boot_ms from position_target_local_ned message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field coordinate_frame from position_target_local_ned message - * - * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - */ -static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field type_mask from position_target_local_ned message - * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - */ -static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field x from position_target_local_ned message - * - * @return X Position in NED frame in meters - */ -static inline float mavlink_msg_position_target_local_ned_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from position_target_local_ned message - * - * @return Y Position in NED frame in meters - */ -static inline float mavlink_msg_position_target_local_ned_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from position_target_local_ned message - * - * @return Z Position in NED frame in meters (note, altitude is negative in NED) - */ -static inline float mavlink_msg_position_target_local_ned_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from position_target_local_ned message - * - * @return X velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_local_ned_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from position_target_local_ned message - * - * @return Y velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_local_ned_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from position_target_local_ned message - * - * @return Z velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_local_ned_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from position_target_local_ned message - * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_local_ned_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from position_target_local_ned message - * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_local_ned_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from position_target_local_ned message - * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from position_target_local_ned message - * - * @return yaw setpoint in rad - */ -static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from position_target_local_ned message - * - * @return yaw rate setpoint in rad/s - */ -static inline float mavlink_msg_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a position_target_local_ned message into a struct - * - * @param msg The message to decode - * @param position_target_local_ned C-struct to decode the message contents into - */ -static inline void mavlink_msg_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_position_target_local_ned_t* position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - position_target_local_ned->time_boot_ms = mavlink_msg_position_target_local_ned_get_time_boot_ms(msg); - position_target_local_ned->x = mavlink_msg_position_target_local_ned_get_x(msg); - position_target_local_ned->y = mavlink_msg_position_target_local_ned_get_y(msg); - position_target_local_ned->z = mavlink_msg_position_target_local_ned_get_z(msg); - position_target_local_ned->vx = mavlink_msg_position_target_local_ned_get_vx(msg); - position_target_local_ned->vy = mavlink_msg_position_target_local_ned_get_vy(msg); - position_target_local_ned->vz = mavlink_msg_position_target_local_ned_get_vz(msg); - position_target_local_ned->afx = mavlink_msg_position_target_local_ned_get_afx(msg); - position_target_local_ned->afy = mavlink_msg_position_target_local_ned_get_afy(msg); - position_target_local_ned->afz = mavlink_msg_position_target_local_ned_get_afz(msg); - position_target_local_ned->yaw = mavlink_msg_position_target_local_ned_get_yaw(msg); - position_target_local_ned->yaw_rate = mavlink_msg_position_target_local_ned_get_yaw_rate(msg); - position_target_local_ned->type_mask = mavlink_msg_position_target_local_ned_get_type_mask(msg); - position_target_local_ned->coordinate_frame = mavlink_msg_position_target_local_ned_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN? msg->len : MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN; - memset(position_target_local_ned, 0, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); - memcpy(position_target_local_ned, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_power_status.h b/include/mavlink/v1.0/common/mavlink_msg_power_status.h deleted file mode 100644 index dca62b5..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_power_status.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE POWER_STATUS PACKING - -#define MAVLINK_MSG_ID_POWER_STATUS 125 - -MAVPACKED( -typedef struct __mavlink_power_status_t { - uint16_t Vcc; /*< 5V rail voltage in millivolts*/ - uint16_t Vservo; /*< servo rail voltage in millivolts*/ - uint16_t flags; /*< power supply status flags (see MAV_POWER_STATUS enum)*/ -}) mavlink_power_status_t; - -#define MAVLINK_MSG_ID_POWER_STATUS_LEN 6 -#define MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN 6 -#define MAVLINK_MSG_ID_125_LEN 6 -#define MAVLINK_MSG_ID_125_MIN_LEN 6 - -#define MAVLINK_MSG_ID_POWER_STATUS_CRC 203 -#define MAVLINK_MSG_ID_125_CRC 203 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \ - 125, \ - "POWER_STATUS", \ - 3, \ - { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \ - { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \ - "POWER_STATUS", \ - 3, \ - { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \ - { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \ - } \ -} -#endif - -/** - * @brief Pack a power_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 Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -} - -/** - * @brief Pack a power_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_power_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t Vcc,uint16_t Vservo,uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -} - -/** - * @brief Encode a power_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param power_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_power_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_power_status_t* power_status) -{ - return mavlink_msg_power_status_pack(system_id, component_id, msg, power_status->Vcc, power_status->Vservo, power_status->flags); -} - -/** - * @brief Encode a power_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param power_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_power_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_power_status_t* power_status) -{ - return mavlink_msg_power_status_pack_chan(system_id, component_id, chan, msg, power_status->Vcc, power_status->Vservo, power_status->flags); -} - -/** - * @brief Send a power_status message - * @param chan MAVLink channel to send the message - * - * @param Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_power_status_send(mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#endif -} - -/** - * @brief Send a power_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_power_status_send_struct(mavlink_channel_t chan, const mavlink_power_status_t* power_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_power_status_send(chan, power_status->Vcc, power_status->Vservo, power_status->flags); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)power_status, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_POWER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_power_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - mavlink_power_status_t *packet = (mavlink_power_status_t *)msgbuf; - packet->Vcc = Vcc; - packet->Vservo = Vservo; - packet->flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE POWER_STATUS UNPACKING - - -/** - * @brief Get field Vcc from power_status message - * - * @return 5V rail voltage in millivolts - */ -static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field Vservo from power_status message - * - * @return servo rail voltage in millivolts - */ -static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field flags from power_status message - * - * @return power supply status flags (see MAV_POWER_STATUS enum) - */ -static inline uint16_t mavlink_msg_power_status_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Decode a power_status message into a struct - * - * @param msg The message to decode - * @param power_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_power_status_decode(const mavlink_message_t* msg, mavlink_power_status_t* power_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - power_status->Vcc = mavlink_msg_power_status_get_Vcc(msg); - power_status->Vservo = mavlink_msg_power_status_get_Vservo(msg); - power_status->flags = mavlink_msg_power_status_get_flags(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_POWER_STATUS_LEN? msg->len : MAVLINK_MSG_ID_POWER_STATUS_LEN; - memset(power_status, 0, MAVLINK_MSG_ID_POWER_STATUS_LEN); - memcpy(power_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_radio_status.h b/include/mavlink/v1.0/common/mavlink_msg_radio_status.h deleted file mode 100644 index 8d266bb..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_radio_status.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE RADIO_STATUS PACKING - -#define MAVLINK_MSG_ID_RADIO_STATUS 109 - -MAVPACKED( -typedef struct __mavlink_radio_status_t { - uint16_t rxerrors; /*< Receive errors*/ - uint16_t fixed; /*< Count of error corrected packets*/ - uint8_t rssi; /*< Local signal strength*/ - uint8_t remrssi; /*< Remote signal strength*/ - uint8_t txbuf; /*< Remaining free buffer space in percent.*/ - uint8_t noise; /*< Background noise level*/ - uint8_t remnoise; /*< Remote background noise level*/ -}) mavlink_radio_status_t; - -#define MAVLINK_MSG_ID_RADIO_STATUS_LEN 9 -#define MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN 9 -#define MAVLINK_MSG_ID_109_LEN 9 -#define MAVLINK_MSG_ID_109_MIN_LEN 9 - -#define MAVLINK_MSG_ID_RADIO_STATUS_CRC 185 -#define MAVLINK_MSG_ID_109_CRC 185 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \ - 109, \ - "RADIO_STATUS", \ - 7, \ - { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ - { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ - { "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) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \ - "RADIO_STATUS", \ - 7, \ - { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ - { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ - { "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) }, \ - } \ -} -#endif - -/** - * @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 Remaining free buffer space in percent. - * @param noise Background noise level - * @param remnoise Remote background noise level - * @param rxerrors Receive errors - * @param fixed Count of error corrected packets - * @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; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -} - -/** - * @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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param rssi Local signal strength - * @param remrssi Remote signal strength - * @param txbuf Remaining free buffer space in percent. - * @param noise Background noise level - * @param remnoise Remote background noise level - * @param rxerrors Receive errors - * @param fixed Count of error corrected packets - * @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; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -} - -/** - * @brief Encode a radio_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param 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 Encode a radio_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param radio_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_radio_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status) -{ - return mavlink_msg_radio_status_pack_chan(system_id, component_id, chan, 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 Remaining free buffer space in percent. - * @param noise Background noise level - * @param remnoise Remote background noise level - * @param rxerrors Receive errors - * @param fixed Count of error corrected packets - */ -#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); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#endif -} - -/** - * @brief Send a radio_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_radio_status_send_struct(mavlink_channel_t chan, const mavlink_radio_status_t* radio_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_radio_status_send(chan, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)radio_status, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RADIO_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_radio_status_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#else - mavlink_radio_status_t *packet = (mavlink_radio_status_t *)msgbuf; - packet->rxerrors = rxerrors; - packet->fixed = fixed; - packet->rssi = rssi; - packet->remrssi = remrssi; - packet->txbuf = txbuf; - packet->noise = noise; - packet->remnoise = remnoise; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#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 Remaining free buffer space in percent. - */ -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 || !MAVLINK_ALIGNED_FIELDS - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_RADIO_STATUS_LEN? msg->len : MAVLINK_MSG_ID_RADIO_STATUS_LEN; - memset(radio_status, 0, MAVLINK_MSG_ID_RADIO_STATUS_LEN); - memcpy(radio_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h b/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h deleted file mode 100644 index 23833bc..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE RAW_IMU PACKING - -#define MAVLINK_MSG_ID_RAW_IMU 27 - -MAVPACKED( -typedef struct __mavlink_raw_imu_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int16_t xacc; /*< X acceleration (raw)*/ - int16_t yacc; /*< Y acceleration (raw)*/ - int16_t zacc; /*< Z acceleration (raw)*/ - int16_t xgyro; /*< Angular speed around X axis (raw)*/ - int16_t ygyro; /*< Angular speed around Y axis (raw)*/ - int16_t zgyro; /*< Angular speed around Z axis (raw)*/ - int16_t xmag; /*< X Magnetic field (raw)*/ - int16_t ymag; /*< Y Magnetic field (raw)*/ - int16_t zmag; /*< Z Magnetic field (raw)*/ -}) mavlink_raw_imu_t; - -#define MAVLINK_MSG_ID_RAW_IMU_LEN 26 -#define MAVLINK_MSG_ID_RAW_IMU_MIN_LEN 26 -#define MAVLINK_MSG_ID_27_LEN 26 -#define MAVLINK_MSG_ID_27_MIN_LEN 26 - -#define MAVLINK_MSG_ID_RAW_IMU_CRC 144 -#define MAVLINK_MSG_ID_27_CRC 144 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RAW_IMU { \ - 27, \ - "RAW_IMU", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RAW_IMU { \ - "RAW_IMU", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ - } \ -} -#endif - -/** - * @brief Pack a raw_imu 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 since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - 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; - - 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, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -} - -/** - * @brief Pack a raw_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - 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; - - 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, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -} - -/** - * @brief Encode a raw_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param raw_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) -{ - return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); -} - -/** - * @brief Encode a raw_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param raw_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) -{ - return mavlink_msg_raw_imu_pack_chan(system_id, component_id, chan, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); -} - -/** - * @brief Send a raw_imu message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _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, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#endif -} - -/** - * @brief Send a raw_imu message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_raw_imu_send_struct(mavlink_channel_t chan, const mavlink_raw_imu_t* raw_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_raw_imu_send(chan, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)raw_imu, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RAW_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, xacc); - _mav_put_int16_t(buf, 10, yacc); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _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, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - mavlink_raw_imu_t *packet = (mavlink_raw_imu_t *)msgbuf; - packet->time_usec = time_usec; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RAW_IMU UNPACKING - - -/** - * @brief Get field time_usec from raw_imu message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field xacc from raw_imu message - * - * @return X acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field yacc from raw_imu message - * - * @return Y acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field zacc from raw_imu message - * - * @return Z acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field xgyro from raw_imu message - * - * @return Angular speed around X axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field ygyro from raw_imu message - * - * @return Angular speed around Y axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field zgyro from raw_imu message - * - * @return Angular speed around Z axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field xmag from raw_imu message - * - * @return X Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field ymag from raw_imu message - * - * @return Y Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field zmag from raw_imu message - * - * @return Z Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 24); -} - -/** - * @brief Decode a raw_imu message into a struct - * - * @param msg The message to decode - * @param raw_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - raw_imu->time_usec = mavlink_msg_raw_imu_get_time_usec(msg); - raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg); - raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg); - raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg); - raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg); - raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg); - raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg); - raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg); - raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg); - raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_IMU_LEN? msg->len : MAVLINK_MSG_ID_RAW_IMU_LEN; - memset(raw_imu, 0, MAVLINK_MSG_ID_RAW_IMU_LEN); - memcpy(raw_imu, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h b/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h deleted file mode 100644 index 2d2ead9..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE RAW_PRESSURE PACKING - -#define MAVLINK_MSG_ID_RAW_PRESSURE 28 - -MAVPACKED( -typedef struct __mavlink_raw_pressure_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int16_t press_abs; /*< Absolute pressure (raw)*/ - int16_t press_diff1; /*< Differential pressure 1 (raw, 0 if nonexistant)*/ - int16_t press_diff2; /*< Differential pressure 2 (raw, 0 if nonexistant)*/ - int16_t temperature; /*< Raw Temperature measurement (raw)*/ -}) mavlink_raw_pressure_t; - -#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 -#define MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN 16 -#define MAVLINK_MSG_ID_28_LEN 16 -#define MAVLINK_MSG_ID_28_MIN_LEN 16 - -#define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67 -#define MAVLINK_MSG_ID_28_CRC 67 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ - 28, \ - "RAW_PRESSURE", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \ - { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ - { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ - { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ - "RAW_PRESSURE", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \ - { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ - { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ - { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a raw_pressure 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 since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) - * @param temperature Raw Temperature measurement (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - - 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, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -} - -/** - * @brief Pack a raw_pressure message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) - * @param temperature Raw Temperature measurement (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - - 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, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -} - -/** - * @brief Encode a raw_pressure struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param raw_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) -{ - return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); -} - -/** - * @brief Encode a raw_pressure struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param raw_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) -{ - return mavlink_msg_raw_pressure_pack_chan(system_id, component_id, chan, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); -} - -/** - * @brief Send a raw_pressure message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) - * @param temperature Raw Temperature measurement (raw) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#endif -} - -/** - * @brief Send a raw_pressure message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_raw_pressure_send_struct(mavlink_channel_t chan, const mavlink_raw_pressure_t* raw_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_raw_pressure_send(chan, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)raw_pressure, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_raw_pressure_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - mavlink_raw_pressure_t *packet = (mavlink_raw_pressure_t *)msgbuf; - packet->time_usec = time_usec; - packet->press_abs = press_abs; - packet->press_diff1 = press_diff1; - packet->press_diff2 = press_diff2; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RAW_PRESSURE UNPACKING - - -/** - * @brief Get field time_usec from raw_pressure message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field press_abs from raw_pressure message - * - * @return Absolute pressure (raw) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field press_diff1 from raw_pressure message - * - * @return Differential pressure 1 (raw, 0 if nonexistant) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field press_diff2 from raw_pressure message - * - * @return Differential pressure 2 (raw, 0 if nonexistant) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field temperature from raw_pressure message - * - * @return Raw Temperature measurement (raw) - */ -static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Decode a raw_pressure message into a struct - * - * @param msg The message to decode - * @param raw_pressure C-struct to decode the message contents into - */ -static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg); - raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg); - raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg); - raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg); - raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_PRESSURE_LEN? msg->len : MAVLINK_MSG_ID_RAW_PRESSURE_LEN; - memset(raw_pressure, 0, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); - memcpy(raw_pressure, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_rc_channels.h b/include/mavlink/v1.0/common/mavlink_msg_rc_channels.h deleted file mode 100644 index f763737..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_rc_channels.h +++ /dev/null @@ -1,713 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS 65 - -MAVPACKED( -typedef struct __mavlink_rc_channels_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan9_raw; /*< RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan10_raw; /*< RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan11_raw; /*< RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan12_raw; /*< RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan13_raw; /*< RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan14_raw; /*< RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan15_raw; /*< RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan16_raw; /*< RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan17_raw; /*< RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan18_raw; /*< RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint8_t chancount; /*< Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ -}) mavlink_rc_channels_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_LEN 42 -#define MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN 42 -#define MAVLINK_MSG_ID_65_LEN 42 -#define MAVLINK_MSG_ID_65_MIN_LEN 42 - -#define MAVLINK_MSG_ID_RC_CHANNELS_CRC 118 -#define MAVLINK_MSG_ID_65_CRC 118 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \ - 65, \ - "RC_CHANNELS", \ - 21, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \ - { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \ - { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \ - { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \ - { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \ - { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \ - { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \ - { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \ - "RC_CHANNELS", \ - 21, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \ - { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \ - { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \ - { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \ - { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \ - { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \ - { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \ - { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels 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_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -} - -/** - * @brief Pack a rc_channels message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t chancount,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,uint16_t chan13_raw,uint16_t chan14_raw,uint16_t chan15_raw,uint16_t chan16_raw,uint16_t chan17_raw,uint16_t chan18_raw,uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -} - -/** - * @brief Encode a rc_channels struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) -{ - return mavlink_msg_rc_channels_pack(system_id, component_id, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); -} - -/** - * @brief Encode a rc_channels struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) -{ - return mavlink_msg_rc_channels_pack_chan(system_id, component_id, chan, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); -} - -/** - * @brief Send a rc_channels message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rc_channels_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#endif -} - -/** - * @brief Send a rc_channels message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_t* rc_channels) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_send(chan, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)rc_channels, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - mavlink_rc_channels_t *packet = (mavlink_rc_channels_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->chan9_raw = chan9_raw; - packet->chan10_raw = chan10_raw; - packet->chan11_raw = chan11_raw; - packet->chan12_raw = chan12_raw; - packet->chan13_raw = chan13_raw; - packet->chan14_raw = chan14_raw; - packet->chan15_raw = chan15_raw; - packet->chan16_raw = chan16_raw; - packet->chan17_raw = chan17_raw; - packet->chan18_raw = chan18_raw; - packet->chancount = chancount; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field chancount from rc_channels message - * - * @return Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - */ -static inline uint8_t mavlink_msg_rc_channels_get_chancount(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field chan1_raw from rc_channels message - * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan2_raw from rc_channels message - * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan3_raw from rc_channels message - * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan4_raw from rc_channels message - * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan5_raw from rc_channels message - * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan6_raw from rc_channels message - * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan7_raw from rc_channels message - * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan8_raw from rc_channels message - * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field chan9_raw from rc_channels message - * - * @return RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field chan10_raw from rc_channels message - * - * @return RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field chan11_raw from rc_channels message - * - * @return RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field chan12_raw from rc_channels message - * - * @return RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field chan13_raw from rc_channels message - * - * @return RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field chan14_raw from rc_channels message - * - * @return RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field chan15_raw from rc_channels message - * - * @return RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field chan16_raw from rc_channels message - * - * @return RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 34); -} - -/** - * @brief Get field chan17_raw from rc_channels message - * - * @return RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 36); -} - -/** - * @brief Get field chan18_raw from rc_channels message - * - * @return RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 38); -} - -/** - * @brief Get field rssi from rc_channels message - * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Decode a rc_channels message into a struct - * - * @param msg The message to decode - * @param rc_channels C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_decode(const mavlink_message_t* msg, mavlink_rc_channels_t* rc_channels) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels->time_boot_ms = mavlink_msg_rc_channels_get_time_boot_ms(msg); - rc_channels->chan1_raw = mavlink_msg_rc_channels_get_chan1_raw(msg); - rc_channels->chan2_raw = mavlink_msg_rc_channels_get_chan2_raw(msg); - rc_channels->chan3_raw = mavlink_msg_rc_channels_get_chan3_raw(msg); - rc_channels->chan4_raw = mavlink_msg_rc_channels_get_chan4_raw(msg); - rc_channels->chan5_raw = mavlink_msg_rc_channels_get_chan5_raw(msg); - rc_channels->chan6_raw = mavlink_msg_rc_channels_get_chan6_raw(msg); - rc_channels->chan7_raw = mavlink_msg_rc_channels_get_chan7_raw(msg); - rc_channels->chan8_raw = mavlink_msg_rc_channels_get_chan8_raw(msg); - rc_channels->chan9_raw = mavlink_msg_rc_channels_get_chan9_raw(msg); - rc_channels->chan10_raw = mavlink_msg_rc_channels_get_chan10_raw(msg); - rc_channels->chan11_raw = mavlink_msg_rc_channels_get_chan11_raw(msg); - rc_channels->chan12_raw = mavlink_msg_rc_channels_get_chan12_raw(msg); - rc_channels->chan13_raw = mavlink_msg_rc_channels_get_chan13_raw(msg); - rc_channels->chan14_raw = mavlink_msg_rc_channels_get_chan14_raw(msg); - rc_channels->chan15_raw = mavlink_msg_rc_channels_get_chan15_raw(msg); - rc_channels->chan16_raw = mavlink_msg_rc_channels_get_chan16_raw(msg); - rc_channels->chan17_raw = mavlink_msg_rc_channels_get_chan17_raw(msg); - rc_channels->chan18_raw = mavlink_msg_rc_channels_get_chan18_raw(msg); - rc_channels->chancount = mavlink_msg_rc_channels_get_chancount(msg); - rc_channels->rssi = mavlink_msg_rc_channels_get_rssi(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_LEN; - memset(rc_channels, 0, MAVLINK_MSG_ID_RC_CHANNELS_LEN); - memcpy(rc_channels, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h b/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h deleted file mode 100644 index 970e926..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS_OVERRIDE PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 - -MAVPACKED( -typedef struct __mavlink_rc_channels_override_t { - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_rc_channels_override_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN 18 -#define MAVLINK_MSG_ID_70_LEN 18 -#define MAVLINK_MSG_ID_70_MIN_LEN 18 - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124 -#define MAVLINK_MSG_ID_70_CRC 124 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ - 70, \ - "RC_CHANNELS_OVERRIDE", \ - 10, \ - { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ - "RC_CHANNELS_OVERRIDE", \ - 10, \ - { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels_override message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - 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; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -} - -/** - * @brief Pack a rc_channels_override message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - 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; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -} - -/** - * @brief Encode a rc_channels_override struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_override C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) -{ - return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); -} - -/** - * @brief Encode a rc_channels_override struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_override C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_override_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) -{ - return mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, chan, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); -} - -/** - * @brief Send a rc_channels_override message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - mavlink_rc_channels_override_t packet; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - 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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#endif -} - -/** - * @brief Send a rc_channels_override message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_override_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_override_t* rc_channels_override) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_override_send(chan, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)rc_channels_override, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_override_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, chan1_raw); - _mav_put_uint16_t(buf, 2, chan2_raw); - _mav_put_uint16_t(buf, 4, chan3_raw); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - mavlink_rc_channels_override_t *packet = (mavlink_rc_channels_override_t *)msgbuf; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - 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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING - - -/** - * @brief Get field target_system from rc_channels_override message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field target_component from rc_channels_override message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field chan1_raw from rc_channels_override message - * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field chan2_raw from rc_channels_override message - * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field chan3_raw from rc_channels_override message - * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan4_raw from rc_channels_override message - * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan5_raw from rc_channels_override message - * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan6_raw from rc_channels_override message - * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan7_raw from rc_channels_override message - * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan8_raw from rc_channels_override message - * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Decode a rc_channels_override message into a struct - * - * @param msg The message to decode - * @param rc_channels_override C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg); - rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg); - rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg); - rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg); - rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg); - rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg); - rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg); - rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN; - memset(rc_channels_override, 0, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); - memcpy(rc_channels_override, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h b/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h deleted file mode 100644 index 87d1b4a..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS_RAW PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 - -MAVPACKED( -typedef struct __mavlink_rc_channels_raw_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ -}) mavlink_rc_channels_raw_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN 22 -#define MAVLINK_MSG_ID_35_LEN 22 -#define MAVLINK_MSG_ID_35_MIN_LEN 22 - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244 -#define MAVLINK_MSG_ID_35_CRC 244 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ - 35, \ - "RC_CHANNELS_RAW", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ - "RC_CHANNELS_RAW", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels_raw 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_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - 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; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -} - -/** - * @brief Pack a rc_channels_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - 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; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -} - -/** - * @brief Encode a rc_channels_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) -{ - return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); -} - -/** - * @brief Encode a rc_channels_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) -{ - return mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, chan, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); -} - -/** - * @brief Send a rc_channels_raw message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - mavlink_rc_channels_raw_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#endif -} - -/** - * @brief Send a rc_channels_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_raw_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_raw_t* rc_channels_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_raw_send(chan, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)rc_channels_raw, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_raw_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - mavlink_rc_channels_raw_t *packet = (mavlink_rc_channels_raw_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->port = port; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_RAW UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels_raw message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from rc_channels_raw message - * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - */ -static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field chan1_raw from rc_channels_raw message - * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan2_raw from rc_channels_raw message - * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan3_raw from rc_channels_raw message - * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan4_raw from rc_channels_raw message - * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan5_raw from rc_channels_raw message - * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan6_raw from rc_channels_raw message - * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan7_raw from rc_channels_raw message - * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan8_raw from rc_channels_raw message - * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field rssi from rc_channels_raw message - * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a rc_channels_raw message into a struct - * - * @param msg The message to decode - * @param rc_channels_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels_raw->time_boot_ms = mavlink_msg_rc_channels_raw_get_time_boot_ms(msg); - rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg); - rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg); - rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg); - rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg); - rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg); - rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg); - rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg); - rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN; - memset(rc_channels_raw, 0, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); - memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h b/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h deleted file mode 100644 index 5b04333..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS_SCALED PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34 - -MAVPACKED( -typedef struct __mavlink_rc_channels_scaled_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t chan1_scaled; /*< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan2_scaled; /*< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan3_scaled; /*< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan4_scaled; /*< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan5_scaled; /*< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan6_scaled; /*< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan7_scaled; /*< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan8_scaled; /*< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ -}) mavlink_rc_channels_scaled_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN 22 -#define MAVLINK_MSG_ID_34_LEN 22 -#define MAVLINK_MSG_ID_34_MIN_LEN 22 - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237 -#define MAVLINK_MSG_ID_34_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ - 34, \ - "RC_CHANNELS_SCALED", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ - { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ - { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ - { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ - { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ - { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ - { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ - { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ - { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ - "RC_CHANNELS_SCALED", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ - { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ - { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ - { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ - { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ - { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ - { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ - { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ - { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels_scaled 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_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - 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; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -} - -/** - * @brief Pack a rc_channels_scaled message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - 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; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -} - -/** - * @brief Encode a rc_channels_scaled struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_scaled C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ - return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); -} - -/** - * @brief Encode a rc_channels_scaled struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_scaled C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ - return mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, chan, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); -} - -/** - * @brief Send a rc_channels_scaled message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - mavlink_rc_channels_scaled_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#endif -} - -/** - * @brief Send a rc_channels_scaled message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_scaled_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_scaled_send(chan, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)rc_channels_scaled, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_scaled_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - mavlink_rc_channels_scaled_t *packet = (mavlink_rc_channels_scaled_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_scaled = chan1_scaled; - packet->chan2_scaled = chan2_scaled; - packet->chan3_scaled = chan3_scaled; - packet->chan4_scaled = chan4_scaled; - packet->chan5_scaled = chan5_scaled; - packet->chan6_scaled = chan6_scaled; - packet->chan7_scaled = chan7_scaled; - packet->chan8_scaled = chan8_scaled; - packet->port = port; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_SCALED UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels_scaled message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from rc_channels_scaled message - * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - */ -static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field chan1_scaled from rc_channels_scaled message - * - * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field chan2_scaled from rc_channels_scaled message - * - * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field chan3_scaled from rc_channels_scaled message - * - * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field chan4_scaled from rc_channels_scaled message - * - * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field chan5_scaled from rc_channels_scaled message - * - * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field chan6_scaled from rc_channels_scaled message - * - * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field chan7_scaled from rc_channels_scaled message - * - * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field chan8_scaled from rc_channels_scaled message - * - * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field rssi from rc_channels_scaled message - * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a rc_channels_scaled message into a struct - * - * @param msg The message to decode - * @param rc_channels_scaled C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels_scaled->time_boot_ms = mavlink_msg_rc_channels_scaled_get_time_boot_ms(msg); - rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg); - rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg); - rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg); - rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg); - rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg); - rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg); - rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg); - rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN; - memset(rc_channels_scaled, 0, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); - memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h b/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h deleted file mode 100644 index 047c2c3..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE REQUEST_DATA_STREAM PACKING - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 - -MAVPACKED( -typedef struct __mavlink_request_data_stream_t { - uint16_t req_message_rate; /*< The requested message rate*/ - uint8_t target_system; /*< The target requested to send the message stream.*/ - uint8_t target_component; /*< The target requested to send the message stream.*/ - uint8_t req_stream_id; /*< The ID of the requested data stream*/ - uint8_t start_stop; /*< 1 to start sending, 0 to stop sending.*/ -}) mavlink_request_data_stream_t; - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN 6 -#define MAVLINK_MSG_ID_66_LEN 6 -#define MAVLINK_MSG_ID_66_MIN_LEN 6 - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148 -#define MAVLINK_MSG_ID_66_CRC 148 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ - 66, \ - "REQUEST_DATA_STREAM", \ - 5, \ - { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ - { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ - { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ - "REQUEST_DATA_STREAM", \ - 5, \ - { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ - { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ - { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ - } \ -} -#endif - -/** - * @brief Pack a request_data_stream message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.req_stream_id = req_stream_id; - packet.start_stop = start_stop; - - 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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -} - -/** - * @brief Pack a request_data_stream message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.req_stream_id = req_stream_id; - packet.start_stop = start_stop; - - 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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -} - -/** - * @brief Encode a request_data_stream struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param request_data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) -{ - return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); -} - -/** - * @brief Encode a request_data_stream struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param request_data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_request_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) -{ - return mavlink_msg_request_data_stream_pack_chan(system_id, component_id, chan, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); -} - -/** - * @brief Send a request_data_stream message - * @param chan MAVLink channel to send the message - * - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - 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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#endif -} - -/** - * @brief Send a request_data_stream message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_request_data_stream_send_struct(mavlink_channel_t chan, const mavlink_request_data_stream_t* request_data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_request_data_stream_send(chan, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)request_data_stream, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#endif -} - -#if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_request_data_stream_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - mavlink_request_data_stream_t *packet = (mavlink_request_data_stream_t *)msgbuf; - packet->req_message_rate = req_message_rate; - packet->target_system = target_system; - packet->target_component = target_component; - 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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#endif -} -#endif - -#endif - -// MESSAGE REQUEST_DATA_STREAM UNPACKING - - -/** - * @brief Get field target_system from request_data_stream message - * - * @return The target requested to send the message stream. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from request_data_stream message - * - * @return The target requested to send the message stream. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field req_stream_id from request_data_stream message - * - * @return The ID of the requested data stream - */ -static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field req_message_rate from request_data_stream message - * - * @return The requested message rate - */ -static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field start_stop from request_data_stream message - * - * @return 1 to start sending, 0 to stop sending. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Decode a request_data_stream message into a struct - * - * @param msg The message to decode - * @param request_data_stream C-struct to decode the message contents into - */ -static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg); - request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg); - request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN? msg->len : MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN; - memset(request_data_stream, 0, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); - memcpy(request_data_stream, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_resource_request.h b/include/mavlink/v1.0/common/mavlink_msg_resource_request.h deleted file mode 100644 index 69a1177..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_resource_request.h +++ /dev/null @@ -1,306 +0,0 @@ -#pragma once -// MESSAGE RESOURCE_REQUEST PACKING - -#define MAVLINK_MSG_ID_RESOURCE_REQUEST 142 - -MAVPACKED( -typedef struct __mavlink_resource_request_t { - uint8_t request_id; /*< Request ID. This ID should be re-used when sending back URI contents*/ - uint8_t uri_type; /*< The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary*/ - uint8_t uri[120]; /*< The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)*/ - uint8_t transfer_type; /*< The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.*/ - uint8_t storage[120]; /*< The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).*/ -}) mavlink_resource_request_t; - -#define MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN 243 -#define MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN 243 -#define MAVLINK_MSG_ID_142_LEN 243 -#define MAVLINK_MSG_ID_142_MIN_LEN 243 - -#define MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC 72 -#define MAVLINK_MSG_ID_142_CRC 72 - -#define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_URI_LEN 120 -#define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_STORAGE_LEN 120 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST { \ - 142, \ - "RESOURCE_REQUEST", \ - 5, \ - { { "request_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_resource_request_t, request_id) }, \ - { "uri_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_resource_request_t, uri_type) }, \ - { "uri", NULL, MAVLINK_TYPE_UINT8_T, 120, 2, offsetof(mavlink_resource_request_t, uri) }, \ - { "transfer_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 122, offsetof(mavlink_resource_request_t, transfer_type) }, \ - { "storage", NULL, MAVLINK_TYPE_UINT8_T, 120, 123, offsetof(mavlink_resource_request_t, storage) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST { \ - "RESOURCE_REQUEST", \ - 5, \ - { { "request_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_resource_request_t, request_id) }, \ - { "uri_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_resource_request_t, uri_type) }, \ - { "uri", NULL, MAVLINK_TYPE_UINT8_T, 120, 2, offsetof(mavlink_resource_request_t, uri) }, \ - { "transfer_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 122, offsetof(mavlink_resource_request_t, transfer_type) }, \ - { "storage", NULL, MAVLINK_TYPE_UINT8_T, 120, 123, offsetof(mavlink_resource_request_t, storage) }, \ - } \ -} -#endif - -/** - * @brief Pack a resource_request 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 request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_resource_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#else - mavlink_resource_request_t packet; - packet.request_id = request_id; - packet.uri_type = uri_type; - packet.transfer_type = transfer_type; - mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -} - -/** - * @brief Pack a resource_request message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_resource_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t request_id,uint8_t uri_type,const uint8_t *uri,uint8_t transfer_type,const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#else - mavlink_resource_request_t packet; - packet.request_id = request_id; - packet.uri_type = uri_type; - packet.transfer_type = transfer_type; - mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -} - -/** - * @brief Encode a resource_request struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param resource_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_resource_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request) -{ - return mavlink_msg_resource_request_pack(system_id, component_id, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); -} - -/** - * @brief Encode a resource_request struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param resource_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_resource_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request) -{ - return mavlink_msg_resource_request_pack_chan(system_id, component_id, chan, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); -} - -/** - * @brief Send a resource_request message - * @param chan MAVLink channel to send the message - * - * @param request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_resource_request_send(mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#else - mavlink_resource_request_t packet; - packet.request_id = request_id; - packet.uri_type = uri_type; - packet.transfer_type = transfer_type; - mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#endif -} - -/** - * @brief Send a resource_request message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_resource_request_send_struct(mavlink_channel_t chan, const mavlink_resource_request_t* resource_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_resource_request_send(chan, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)resource_request, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_resource_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#else - mavlink_resource_request_t *packet = (mavlink_resource_request_t *)msgbuf; - packet->request_id = request_id; - packet->uri_type = uri_type; - packet->transfer_type = transfer_type; - mav_array_memcpy(packet->uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet->storage, storage, sizeof(uint8_t)*120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RESOURCE_REQUEST UNPACKING - - -/** - * @brief Get field request_id from resource_request message - * - * @return Request ID. This ID should be re-used when sending back URI contents - */ -static inline uint8_t mavlink_msg_resource_request_get_request_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field uri_type from resource_request message - * - * @return The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - */ -static inline uint8_t mavlink_msg_resource_request_get_uri_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field uri from resource_request message - * - * @return The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - */ -static inline uint16_t mavlink_msg_resource_request_get_uri(const mavlink_message_t* msg, uint8_t *uri) -{ - return _MAV_RETURN_uint8_t_array(msg, uri, 120, 2); -} - -/** - * @brief Get field transfer_type from resource_request message - * - * @return The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - */ -static inline uint8_t mavlink_msg_resource_request_get_transfer_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 122); -} - -/** - * @brief Get field storage from resource_request message - * - * @return The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - */ -static inline uint16_t mavlink_msg_resource_request_get_storage(const mavlink_message_t* msg, uint8_t *storage) -{ - return _MAV_RETURN_uint8_t_array(msg, storage, 120, 123); -} - -/** - * @brief Decode a resource_request message into a struct - * - * @param msg The message to decode - * @param resource_request C-struct to decode the message contents into - */ -static inline void mavlink_msg_resource_request_decode(const mavlink_message_t* msg, mavlink_resource_request_t* resource_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - resource_request->request_id = mavlink_msg_resource_request_get_request_id(msg); - resource_request->uri_type = mavlink_msg_resource_request_get_uri_type(msg); - mavlink_msg_resource_request_get_uri(msg, resource_request->uri); - resource_request->transfer_type = mavlink_msg_resource_request_get_transfer_type(msg); - mavlink_msg_resource_request_get_storage(msg, resource_request->storage); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN; - memset(resource_request, 0, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); - memcpy(resource_request, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h b/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h deleted file mode 100644 index cad1c19..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE SAFETY_ALLOWED_AREA PACKING - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 - -MAVPACKED( -typedef struct __mavlink_safety_allowed_area_t { - float p1x; /*< x position 1 / Latitude 1*/ - float p1y; /*< y position 1 / Longitude 1*/ - float p1z; /*< z position 1 / Altitude 1*/ - float p2x; /*< x position 2 / Latitude 2*/ - float p2y; /*< y position 2 / Longitude 2*/ - float p2z; /*< z position 2 / Altitude 2*/ - uint8_t frame; /*< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ -}) mavlink_safety_allowed_area_t; - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN 25 -#define MAVLINK_MSG_ID_55_LEN 25 -#define MAVLINK_MSG_ID_55_MIN_LEN 25 - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3 -#define MAVLINK_MSG_ID_55_CRC 3 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ - 55, \ - "SAFETY_ALLOWED_AREA", \ - 7, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ - "SAFETY_ALLOWED_AREA", \ - 7, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a safety_allowed_area 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 frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - - 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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -} - -/** - * @brief Pack a safety_allowed_area message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - - 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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -} - -/** - * @brief Encode a safety_allowed_area struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param safety_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) -{ - return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); -} - -/** - * @brief Encode a safety_allowed_area struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param safety_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) -{ - return mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); -} - -/** - * @brief Send a safety_allowed_area message - * @param chan MAVLink channel to send the message - * - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#endif -} - -/** - * @brief Send a safety_allowed_area message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_safety_allowed_area_send_struct(mavlink_channel_t chan, const mavlink_safety_allowed_area_t* safety_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_safety_allowed_area_send(chan, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)safety_allowed_area, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_safety_allowed_area_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - mavlink_safety_allowed_area_t *packet = (mavlink_safety_allowed_area_t *)msgbuf; - packet->p1x = p1x; - packet->p1y = p1y; - packet->p1z = p1z; - packet->p2x = p2x; - packet->p2y = p2y; - packet->p2z = p2z; - packet->frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SAFETY_ALLOWED_AREA UNPACKING - - -/** - * @brief Get field frame from safety_allowed_area message - * - * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - */ -static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field p1x from safety_allowed_area message - * - * @return x position 1 / Latitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field p1y from safety_allowed_area message - * - * @return y position 1 / Longitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field p1z from safety_allowed_area message - * - * @return z position 1 / Altitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field p2x from safety_allowed_area message - * - * @return x position 2 / Latitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field p2y from safety_allowed_area message - * - * @return y position 2 / Longitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field p2z from safety_allowed_area message - * - * @return z position 2 / Altitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a safety_allowed_area message into a struct - * - * @param msg The message to decode - * @param safety_allowed_area C-struct to decode the message contents into - */ -static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg); - safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg); - safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg); - safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg); - safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN? msg->len : MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN; - memset(safety_allowed_area, 0, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); - memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h b/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h deleted file mode 100644 index 293c1f0..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h +++ /dev/null @@ -1,413 +0,0 @@ -#pragma once -// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 - -MAVPACKED( -typedef struct __mavlink_safety_set_allowed_area_t { - float p1x; /*< x position 1 / Latitude 1*/ - float p1y; /*< y position 1 / Longitude 1*/ - float p1z; /*< z position 1 / Altitude 1*/ - float p2x; /*< x position 2 / Latitude 2*/ - float p2y; /*< y position 2 / Longitude 2*/ - float p2z; /*< z position 2 / Altitude 2*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ -}) mavlink_safety_set_allowed_area_t; - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN 27 -#define MAVLINK_MSG_ID_54_LEN 27 -#define MAVLINK_MSG_ID_54_MIN_LEN 27 - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15 -#define MAVLINK_MSG_ID_54_CRC 15 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ - 54, \ - "SAFETY_SET_ALLOWED_AREA", \ - 9, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ - "SAFETY_SET_ALLOWED_AREA", \ - 9, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a safety_set_allowed_area message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - - 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; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - - 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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -} - -/** - * @brief Pack a safety_set_allowed_area message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - - 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; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - - 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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -} - -/** - * @brief Encode a safety_set_allowed_area struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param safety_set_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ - return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); -} - -/** - * @brief Encode a safety_set_allowed_area struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param safety_set_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ - return mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); -} - -/** - * @brief Send a safety_set_allowed_area message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - mavlink_safety_set_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#endif -} - -/** - * @brief Send a safety_set_allowed_area message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_safety_set_allowed_area_send_struct(mavlink_channel_t chan, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_safety_set_allowed_area_send(chan, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)safety_set_allowed_area, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_safety_set_allowed_area_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - mavlink_safety_set_allowed_area_t *packet = (mavlink_safety_set_allowed_area_t *)msgbuf; - packet->p1x = p1x; - packet->p1y = p1y; - packet->p1z = p1z; - packet->p2x = p2x; - packet->p2y = p2y; - packet->p2z = p2z; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING - - -/** - * @brief Get field target_system from safety_set_allowed_area message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field target_component from safety_set_allowed_area message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field frame from safety_set_allowed_area message - * - * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field p1x from safety_set_allowed_area message - * - * @return x position 1 / Latitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field p1y from safety_set_allowed_area message - * - * @return y position 1 / Longitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field p1z from safety_set_allowed_area message - * - * @return z position 1 / Altitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field p2x from safety_set_allowed_area message - * - * @return x position 2 / Latitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field p2y from safety_set_allowed_area message - * - * @return y position 2 / Longitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field p2z from safety_set_allowed_area message - * - * @return z position 2 / Altitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a safety_set_allowed_area message into a struct - * - * @param msg The message to decode - * @param safety_set_allowed_area C-struct to decode the message contents into - */ -static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg); - safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg); - safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg); - safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg); - safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg); - safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg); - safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN? msg->len : MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN; - memset(safety_set_allowed_area, 0, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); - memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h b/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h deleted file mode 100644 index 2994d99..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE SCALED_IMU PACKING - -#define MAVLINK_MSG_ID_SCALED_IMU 26 - -MAVPACKED( -typedef struct __mavlink_scaled_imu_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ - int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ - int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ - int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ - int16_t xmag; /*< X Magnetic field (milli tesla)*/ - int16_t ymag; /*< Y Magnetic field (milli tesla)*/ - int16_t zmag; /*< Z Magnetic field (milli tesla)*/ -}) mavlink_scaled_imu_t; - -#define MAVLINK_MSG_ID_SCALED_IMU_LEN 22 -#define MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN 22 -#define MAVLINK_MSG_ID_26_LEN 22 -#define MAVLINK_MSG_ID_26_MIN_LEN 22 - -#define MAVLINK_MSG_ID_SCALED_IMU_CRC 170 -#define MAVLINK_MSG_ID_26_CRC 170 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ - 26, \ - "SCALED_IMU", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ - "SCALED_IMU", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_imu 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_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - 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; - 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; - - 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, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -} - -/** - * @brief Pack a scaled_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - 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; - 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; - - 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, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -} - -/** - * @brief Encode a scaled_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) -{ - return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); -} - -/** - * @brief Encode a scaled_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) -{ - return mavlink_msg_scaled_imu_pack_chan(system_id, component_id, chan, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); -} - -/** - * @brief Send a scaled_imu message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _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, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - mavlink_scaled_imu_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#endif -} - -/** - * @brief Send a scaled_imu message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_imu_send_struct(mavlink_channel_t chan, const mavlink_scaled_imu_t* scaled_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_imu_send(chan, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)scaled_imu, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_imu_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _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, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - mavlink_scaled_imu_t *packet = (mavlink_scaled_imu_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_IMU UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_imu message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field xacc from scaled_imu message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field yacc from scaled_imu message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field zacc from scaled_imu message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field xgyro from scaled_imu message - * - * @return Angular speed around X axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field ygyro from scaled_imu message - * - * @return Angular speed around Y axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field zgyro from scaled_imu message - * - * @return Angular speed around Z axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field xmag from scaled_imu message - * - * @return X Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field ymag from scaled_imu message - * - * @return Y Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field zmag from scaled_imu message - * - * @return Z Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Decode a scaled_imu message into a struct - * - * @param msg The message to decode - * @param scaled_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_imu->time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg); - scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg); - scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg); - scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg); - scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg); - scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg); - scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg); - scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg); - scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg); - scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_IMU_LEN? msg->len : MAVLINK_MSG_ID_SCALED_IMU_LEN; - memset(scaled_imu, 0, MAVLINK_MSG_ID_SCALED_IMU_LEN); - memcpy(scaled_imu, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h b/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h deleted file mode 100644 index c232691..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE SCALED_IMU2 PACKING - -#define MAVLINK_MSG_ID_SCALED_IMU2 116 - -MAVPACKED( -typedef struct __mavlink_scaled_imu2_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ - int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ - int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ - int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ - int16_t xmag; /*< X Magnetic field (milli tesla)*/ - int16_t ymag; /*< Y Magnetic field (milli tesla)*/ - int16_t zmag; /*< Z Magnetic field (milli tesla)*/ -}) mavlink_scaled_imu2_t; - -#define MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 -#define MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN 22 -#define MAVLINK_MSG_ID_116_LEN 22 -#define MAVLINK_MSG_ID_116_MIN_LEN 22 - -#define MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 -#define MAVLINK_MSG_ID_116_CRC 76 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \ - 116, \ - "SCALED_IMU2", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \ - "SCALED_IMU2", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_imu2 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_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -} - -/** - * @brief Pack a scaled_imu2 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -} - -/** - * @brief Encode a scaled_imu2 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_imu2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) -{ - return mavlink_msg_scaled_imu2_pack(system_id, component_id, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); -} - -/** - * @brief Encode a scaled_imu2 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_imu2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) -{ - return mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, chan, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); -} - -/** - * @brief Send a scaled_imu2 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_imu2_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[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#endif -} - -/** - * @brief Send a scaled_imu2 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_imu2_send_struct(mavlink_channel_t chan, const mavlink_scaled_imu2_t* scaled_imu2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_imu2_send(chan, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)scaled_imu2, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_IMU2_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_imu2_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - mavlink_scaled_imu2_t *packet = (mavlink_scaled_imu2_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_IMU2 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_imu2 message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field xacc from scaled_imu2 message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field yacc from scaled_imu2 message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field zacc from scaled_imu2 message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field xgyro from scaled_imu2 message - * - * @return Angular speed around X axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field ygyro from scaled_imu2 message - * - * @return Angular speed around Y axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field zgyro from scaled_imu2 message - * - * @return Angular speed around Z axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field xmag from scaled_imu2 message - * - * @return X Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field ymag from scaled_imu2 message - * - * @return Y Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field zmag from scaled_imu2 message - * - * @return Z Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Decode a scaled_imu2 message into a struct - * - * @param msg The message to decode - * @param scaled_imu2 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_imu2_decode(const mavlink_message_t* msg, mavlink_scaled_imu2_t* scaled_imu2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_imu2->time_boot_ms = mavlink_msg_scaled_imu2_get_time_boot_ms(msg); - scaled_imu2->xacc = mavlink_msg_scaled_imu2_get_xacc(msg); - scaled_imu2->yacc = mavlink_msg_scaled_imu2_get_yacc(msg); - scaled_imu2->zacc = mavlink_msg_scaled_imu2_get_zacc(msg); - scaled_imu2->xgyro = mavlink_msg_scaled_imu2_get_xgyro(msg); - scaled_imu2->ygyro = mavlink_msg_scaled_imu2_get_ygyro(msg); - scaled_imu2->zgyro = mavlink_msg_scaled_imu2_get_zgyro(msg); - scaled_imu2->xmag = mavlink_msg_scaled_imu2_get_xmag(msg); - scaled_imu2->ymag = mavlink_msg_scaled_imu2_get_ymag(msg); - scaled_imu2->zmag = mavlink_msg_scaled_imu2_get_zmag(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_IMU2_LEN? msg->len : MAVLINK_MSG_ID_SCALED_IMU2_LEN; - memset(scaled_imu2, 0, MAVLINK_MSG_ID_SCALED_IMU2_LEN); - memcpy(scaled_imu2, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_scaled_imu3.h b/include/mavlink/v1.0/common/mavlink_msg_scaled_imu3.h deleted file mode 100644 index 22b9d86..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_scaled_imu3.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE SCALED_IMU3 PACKING - -#define MAVLINK_MSG_ID_SCALED_IMU3 129 - -MAVPACKED( -typedef struct __mavlink_scaled_imu3_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ - int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ - int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ - int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ - int16_t xmag; /*< X Magnetic field (milli tesla)*/ - int16_t ymag; /*< Y Magnetic field (milli tesla)*/ - int16_t zmag; /*< Z Magnetic field (milli tesla)*/ -}) mavlink_scaled_imu3_t; - -#define MAVLINK_MSG_ID_SCALED_IMU3_LEN 22 -#define MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN 22 -#define MAVLINK_MSG_ID_129_LEN 22 -#define MAVLINK_MSG_ID_129_MIN_LEN 22 - -#define MAVLINK_MSG_ID_SCALED_IMU3_CRC 46 -#define MAVLINK_MSG_ID_129_CRC 46 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_IMU3 { \ - 129, \ - "SCALED_IMU3", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu3_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu3_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu3_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu3_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu3_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu3_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu3_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu3_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu3_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu3_t, zmag) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_IMU3 { \ - "SCALED_IMU3", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu3_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu3_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu3_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu3_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu3_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu3_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu3_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu3_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu3_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu3_t, zmag) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_imu3 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_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#else - mavlink_scaled_imu3_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -} - -/** - * @brief Pack a scaled_imu3 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#else - mavlink_scaled_imu3_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -} - -/** - * @brief Encode a scaled_imu3 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_imu3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3) -{ - return mavlink_msg_scaled_imu3_pack(system_id, component_id, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag); -} - -/** - * @brief Encode a scaled_imu3 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_imu3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3) -{ - return mavlink_msg_scaled_imu3_pack_chan(system_id, component_id, chan, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag); -} - -/** - * @brief Send a scaled_imu3 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_imu3_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[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#else - mavlink_scaled_imu3_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#endif -} - -/** - * @brief Send a scaled_imu3 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_imu3_send_struct(mavlink_channel_t chan, const mavlink_scaled_imu3_t* scaled_imu3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_imu3_send(chan, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)scaled_imu3, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_IMU3_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_imu3_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#else - mavlink_scaled_imu3_t *packet = (mavlink_scaled_imu3_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_IMU3 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_imu3 message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_imu3_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field xacc from scaled_imu3 message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field yacc from scaled_imu3 message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field zacc from scaled_imu3 message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field xgyro from scaled_imu3 message - * - * @return Angular speed around X axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field ygyro from scaled_imu3 message - * - * @return Angular speed around Y axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field zgyro from scaled_imu3 message - * - * @return Angular speed around Z axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field xmag from scaled_imu3 message - * - * @return X Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field ymag from scaled_imu3 message - * - * @return Y Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field zmag from scaled_imu3 message - * - * @return Z Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Decode a scaled_imu3 message into a struct - * - * @param msg The message to decode - * @param scaled_imu3 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_imu3_decode(const mavlink_message_t* msg, mavlink_scaled_imu3_t* scaled_imu3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_imu3->time_boot_ms = mavlink_msg_scaled_imu3_get_time_boot_ms(msg); - scaled_imu3->xacc = mavlink_msg_scaled_imu3_get_xacc(msg); - scaled_imu3->yacc = mavlink_msg_scaled_imu3_get_yacc(msg); - scaled_imu3->zacc = mavlink_msg_scaled_imu3_get_zacc(msg); - scaled_imu3->xgyro = mavlink_msg_scaled_imu3_get_xgyro(msg); - scaled_imu3->ygyro = mavlink_msg_scaled_imu3_get_ygyro(msg); - scaled_imu3->zgyro = mavlink_msg_scaled_imu3_get_zgyro(msg); - scaled_imu3->xmag = mavlink_msg_scaled_imu3_get_xmag(msg); - scaled_imu3->ymag = mavlink_msg_scaled_imu3_get_ymag(msg); - scaled_imu3->zmag = mavlink_msg_scaled_imu3_get_zmag(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_IMU3_LEN? msg->len : MAVLINK_MSG_ID_SCALED_IMU3_LEN; - memset(scaled_imu3, 0, MAVLINK_MSG_ID_SCALED_IMU3_LEN); - memcpy(scaled_imu3, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h b/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h deleted file mode 100644 index 0dcfc92..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE SCALED_PRESSURE PACKING - -#define MAVLINK_MSG_ID_SCALED_PRESSURE 29 - -MAVPACKED( -typedef struct __mavlink_scaled_pressure_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float press_abs; /*< Absolute pressure (hectopascal)*/ - float press_diff; /*< Differential pressure 1 (hectopascal)*/ - int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ -}) mavlink_scaled_pressure_t; - -#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14 -#define MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN 14 -#define MAVLINK_MSG_ID_29_LEN 14 -#define MAVLINK_MSG_ID_29_MIN_LEN 14 - -#define MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115 -#define MAVLINK_MSG_ID_29_CRC 115 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ - 29, \ - "SCALED_PRESSURE", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ - "SCALED_PRESSURE", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_pressure 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_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - 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, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -} - -/** - * @brief Pack a scaled_pressure message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - 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, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -} - -/** - * @brief Encode a scaled_pressure struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) -{ - return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); -} - -/** - * @brief Encode a scaled_pressure struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) -{ - return mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, chan, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); -} - -/** - * @brief Send a scaled_pressure message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#endif -} - -/** - * @brief Send a scaled_pressure message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_pressure_send_struct(mavlink_channel_t chan, const mavlink_scaled_pressure_t* scaled_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_pressure_send(chan, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)scaled_pressure, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_pressure_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - mavlink_scaled_pressure_t *packet = (mavlink_scaled_pressure_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->press_abs = press_abs; - packet->press_diff = press_diff; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_PRESSURE UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_pressure message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field press_abs from scaled_pressure message - * - * @return Absolute pressure (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field press_diff from scaled_pressure message - * - * @return Differential pressure 1 (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field temperature from scaled_pressure message - * - * @return Temperature measurement (0.01 degrees celsius) - */ -static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Decode a scaled_pressure message into a struct - * - * @param msg The message to decode - * @param scaled_pressure C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_pressure->time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg); - scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg); - scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg); - scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_PRESSURE_LEN? msg->len : MAVLINK_MSG_ID_SCALED_PRESSURE_LEN; - memset(scaled_pressure, 0, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); - memcpy(scaled_pressure, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure2.h b/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure2.h deleted file mode 100644 index 1e7920b..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure2.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE SCALED_PRESSURE2 PACKING - -#define MAVLINK_MSG_ID_SCALED_PRESSURE2 137 - -MAVPACKED( -typedef struct __mavlink_scaled_pressure2_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float press_abs; /*< Absolute pressure (hectopascal)*/ - float press_diff; /*< Differential pressure 1 (hectopascal)*/ - int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ -}) mavlink_scaled_pressure2_t; - -#define MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN 14 -#define MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN 14 -#define MAVLINK_MSG_ID_137_LEN 14 -#define MAVLINK_MSG_ID_137_MIN_LEN 14 - -#define MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC 195 -#define MAVLINK_MSG_ID_137_CRC 195 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2 { \ - 137, \ - "SCALED_PRESSURE2", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure2_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure2_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure2_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure2_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2 { \ - "SCALED_PRESSURE2", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure2_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure2_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure2_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure2_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_pressure2 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_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_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, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#else - mavlink_scaled_pressure2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE2; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -} - -/** - * @brief Pack a scaled_pressure2 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_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, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#else - mavlink_scaled_pressure2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE2; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -} - -/** - * @brief Encode a scaled_pressure2 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure2_t* scaled_pressure2) -{ - return mavlink_msg_scaled_pressure2_pack(system_id, component_id, msg, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature); -} - -/** - * @brief Encode a scaled_pressure2 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure2_t* scaled_pressure2) -{ - return mavlink_msg_scaled_pressure2_pack_chan(system_id, component_id, chan, msg, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature); -} - -/** - * @brief Send a scaled_pressure2 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_pressure2_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[MAVLINK_MSG_ID_SCALED_PRESSURE2_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_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#else - mavlink_scaled_pressure2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#endif -} - -/** - * @brief Send a scaled_pressure2 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_pressure2_send_struct(mavlink_channel_t chan, const mavlink_scaled_pressure2_t* scaled_pressure2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_pressure2_send(chan, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)scaled_pressure2, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_pressure2_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#else - mavlink_scaled_pressure2_t *packet = (mavlink_scaled_pressure2_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->press_abs = press_abs; - packet->press_diff = press_diff; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_PRESSURE2 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_pressure2 message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_pressure2_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field press_abs from scaled_pressure2 message - * - * @return Absolute pressure (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure2_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field press_diff from scaled_pressure2 message - * - * @return Differential pressure 1 (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure2_get_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field temperature from scaled_pressure2 message - * - * @return Temperature measurement (0.01 degrees celsius) - */ -static inline int16_t mavlink_msg_scaled_pressure2_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Decode a scaled_pressure2 message into a struct - * - * @param msg The message to decode - * @param scaled_pressure2 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_pressure2_decode(const mavlink_message_t* msg, mavlink_scaled_pressure2_t* scaled_pressure2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_pressure2->time_boot_ms = mavlink_msg_scaled_pressure2_get_time_boot_ms(msg); - scaled_pressure2->press_abs = mavlink_msg_scaled_pressure2_get_press_abs(msg); - scaled_pressure2->press_diff = mavlink_msg_scaled_pressure2_get_press_diff(msg); - scaled_pressure2->temperature = mavlink_msg_scaled_pressure2_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN? msg->len : MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN; - memset(scaled_pressure2, 0, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); - memcpy(scaled_pressure2, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure3.h b/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure3.h deleted file mode 100644 index a0b6586..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure3.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE SCALED_PRESSURE3 PACKING - -#define MAVLINK_MSG_ID_SCALED_PRESSURE3 143 - -MAVPACKED( -typedef struct __mavlink_scaled_pressure3_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float press_abs; /*< Absolute pressure (hectopascal)*/ - float press_diff; /*< Differential pressure 1 (hectopascal)*/ - int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ -}) mavlink_scaled_pressure3_t; - -#define MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN 14 -#define MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN 14 -#define MAVLINK_MSG_ID_143_LEN 14 -#define MAVLINK_MSG_ID_143_MIN_LEN 14 - -#define MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC 131 -#define MAVLINK_MSG_ID_143_CRC 131 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3 { \ - 143, \ - "SCALED_PRESSURE3", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure3_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure3_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure3_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure3_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3 { \ - "SCALED_PRESSURE3", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure3_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure3_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure3_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure3_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_pressure3 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_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_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, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#else - mavlink_scaled_pressure3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE3; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -} - -/** - * @brief Pack a scaled_pressure3 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_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, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#else - mavlink_scaled_pressure3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE3; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -} - -/** - * @brief Encode a scaled_pressure3 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure3_t* scaled_pressure3) -{ - return mavlink_msg_scaled_pressure3_pack(system_id, component_id, msg, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature); -} - -/** - * @brief Encode a scaled_pressure3 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure3_t* scaled_pressure3) -{ - return mavlink_msg_scaled_pressure3_pack_chan(system_id, component_id, chan, msg, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature); -} - -/** - * @brief Send a scaled_pressure3 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_pressure3_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[MAVLINK_MSG_ID_SCALED_PRESSURE3_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_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#else - mavlink_scaled_pressure3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#endif -} - -/** - * @brief Send a scaled_pressure3 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_pressure3_send_struct(mavlink_channel_t chan, const mavlink_scaled_pressure3_t* scaled_pressure3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_pressure3_send(chan, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)scaled_pressure3, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_pressure3_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#else - mavlink_scaled_pressure3_t *packet = (mavlink_scaled_pressure3_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->press_abs = press_abs; - packet->press_diff = press_diff; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_PRESSURE3 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_pressure3 message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_pressure3_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field press_abs from scaled_pressure3 message - * - * @return Absolute pressure (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure3_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field press_diff from scaled_pressure3 message - * - * @return Differential pressure 1 (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure3_get_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field temperature from scaled_pressure3 message - * - * @return Temperature measurement (0.01 degrees celsius) - */ -static inline int16_t mavlink_msg_scaled_pressure3_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Decode a scaled_pressure3 message into a struct - * - * @param msg The message to decode - * @param scaled_pressure3 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_pressure3_decode(const mavlink_message_t* msg, mavlink_scaled_pressure3_t* scaled_pressure3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_pressure3->time_boot_ms = mavlink_msg_scaled_pressure3_get_time_boot_ms(msg); - scaled_pressure3->press_abs = mavlink_msg_scaled_pressure3_get_press_abs(msg); - scaled_pressure3->press_diff = mavlink_msg_scaled_pressure3_get_press_diff(msg); - scaled_pressure3->temperature = mavlink_msg_scaled_pressure3_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN? msg->len : MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN; - memset(scaled_pressure3, 0, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); - memcpy(scaled_pressure3, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_serial_control.h b/include/mavlink/v1.0/common/mavlink_msg_serial_control.h deleted file mode 100644 index ce95811..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_serial_control.h +++ /dev/null @@ -1,330 +0,0 @@ -#pragma once -// MESSAGE SERIAL_CONTROL PACKING - -#define MAVLINK_MSG_ID_SERIAL_CONTROL 126 - -MAVPACKED( -typedef struct __mavlink_serial_control_t { - uint32_t baudrate; /*< Baudrate of transfer. Zero means no change.*/ - uint16_t timeout; /*< Timeout for reply data in milliseconds*/ - uint8_t device; /*< See SERIAL_CONTROL_DEV enum*/ - uint8_t flags; /*< See SERIAL_CONTROL_FLAG enum*/ - uint8_t count; /*< how many bytes in this transfer*/ - uint8_t data[70]; /*< serial data*/ -}) mavlink_serial_control_t; - -#define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79 -#define MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN 79 -#define MAVLINK_MSG_ID_126_LEN 79 -#define MAVLINK_MSG_ID_126_MIN_LEN 79 - -#define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220 -#define MAVLINK_MSG_ID_126_CRC 220 - -#define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN 70 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \ - 126, \ - "SERIAL_CONTROL", \ - 6, \ - { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ - { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \ - "SERIAL_CONTROL", \ - 6, \ - { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ - { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a serial_control 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 device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -} - -/** - * @brief Pack a serial_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t device,uint8_t flags,uint16_t timeout,uint32_t baudrate,uint8_t count,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -} - -/** - * @brief Encode a serial_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) -{ - return mavlink_msg_serial_control_pack(system_id, component_id, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); -} - -/** - * @brief Encode a serial_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) -{ - return mavlink_msg_serial_control_pack_chan(system_id, component_id, chan, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); -} - -/** - * @brief Send a serial_control message - * @param chan MAVLink channel to send the message - * - * @param device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_control_send(mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#endif -} - -/** - * @brief Send a serial_control message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_serial_control_send_struct(mavlink_channel_t chan, const mavlink_serial_control_t* serial_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_serial_control_send(chan, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)serial_control, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - mavlink_serial_control_t *packet = (mavlink_serial_control_t *)msgbuf; - packet->baudrate = baudrate; - packet->timeout = timeout; - packet->device = device; - packet->flags = flags; - packet->count = count; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_CONTROL UNPACKING - - -/** - * @brief Get field device from serial_control message - * - * @return See SERIAL_CONTROL_DEV enum - */ -static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field flags from serial_control message - * - * @return See SERIAL_CONTROL_FLAG enum - */ -static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field timeout from serial_control message - * - * @return Timeout for reply data in milliseconds - */ -static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field baudrate from serial_control message - * - * @return Baudrate of transfer. Zero means no change. - */ -static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from serial_control message - * - * @return how many bytes in this transfer - */ -static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field data from serial_control message - * - * @return serial data - */ -static inline uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 70, 9); -} - -/** - * @brief Decode a serial_control message into a struct - * - * @param msg The message to decode - * @param serial_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_control_decode(const mavlink_message_t* msg, mavlink_serial_control_t* serial_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - serial_control->baudrate = mavlink_msg_serial_control_get_baudrate(msg); - serial_control->timeout = mavlink_msg_serial_control_get_timeout(msg); - serial_control->device = mavlink_msg_serial_control_get_device(msg); - serial_control->flags = mavlink_msg_serial_control_get_flags(msg); - serial_control->count = mavlink_msg_serial_control_get_count(msg); - mavlink_msg_serial_control_get_data(msg, serial_control->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SERIAL_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_SERIAL_CONTROL_LEN; - memset(serial_control, 0, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); - memcpy(serial_control, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h b/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h deleted file mode 100644 index 0bf3936..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE SERVO_OUTPUT_RAW PACKING - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36 - -MAVPACKED( -typedef struct __mavlink_servo_output_raw_t { - uint32_t time_usec; /*< Timestamp (microseconds since system boot)*/ - uint16_t servo1_raw; /*< Servo output 1 value, in microseconds*/ - uint16_t servo2_raw; /*< Servo output 2 value, in microseconds*/ - uint16_t servo3_raw; /*< Servo output 3 value, in microseconds*/ - uint16_t servo4_raw; /*< Servo output 4 value, in microseconds*/ - uint16_t servo5_raw; /*< Servo output 5 value, in microseconds*/ - uint16_t servo6_raw; /*< Servo output 6 value, in microseconds*/ - uint16_t servo7_raw; /*< Servo output 7 value, in microseconds*/ - uint16_t servo8_raw; /*< Servo output 8 value, in microseconds*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.*/ -}) mavlink_servo_output_raw_t; - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21 -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN 21 -#define MAVLINK_MSG_ID_36_LEN 21 -#define MAVLINK_MSG_ID_36_MIN_LEN 21 - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC 222 -#define MAVLINK_MSG_ID_36_CRC 222 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ - 36, \ - "SERVO_OUTPUT_RAW", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ - { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ - { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ - { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ - { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ - { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ - { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ - { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ - { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ - "SERVO_OUTPUT_RAW", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ - { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ - { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ - { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ - { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ - { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ - { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ - { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ - { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ - } \ -} -#endif - -/** - * @brief Pack a servo_output_raw 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 since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - - 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; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - - 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, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -} - -/** - * @brief Pack a servo_output_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - - 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; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - - 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, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -} - -/** - * @brief Encode a servo_output_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param servo_output_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) -{ - return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); -} - -/** - * @brief Encode a servo_output_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param servo_output_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_servo_output_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) -{ - return mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, chan, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); -} - -/** - * @brief Send a servo_output_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _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, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - mavlink_servo_output_raw_t packet; - packet.time_usec = time_usec; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#endif -} - -/** - * @brief Send a servo_output_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_servo_output_raw_send_struct(mavlink_channel_t chan, const mavlink_servo_output_raw_t* servo_output_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_servo_output_raw_send(chan, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)servo_output_raw, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_servo_output_raw_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 4, servo1_raw); - _mav_put_uint16_t(buf, 6, servo2_raw); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _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, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - mavlink_servo_output_raw_t *packet = (mavlink_servo_output_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->servo1_raw = servo1_raw; - packet->servo2_raw = servo2_raw; - packet->servo3_raw = servo3_raw; - packet->servo4_raw = servo4_raw; - packet->servo5_raw = servo5_raw; - packet->servo6_raw = servo6_raw; - packet->servo7_raw = servo7_raw; - packet->servo8_raw = servo8_raw; - packet->port = port; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SERVO_OUTPUT_RAW UNPACKING - - -/** - * @brief Get field time_usec from servo_output_raw message - * - * @return Timestamp (microseconds since system boot) - */ -static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from servo_output_raw message - * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - */ -static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field servo1_raw from servo_output_raw message - * - * @return Servo output 1 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field servo2_raw from servo_output_raw message - * - * @return Servo output 2 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field servo3_raw from servo_output_raw message - * - * @return Servo output 3 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field servo4_raw from servo_output_raw message - * - * @return Servo output 4 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field servo5_raw from servo_output_raw message - * - * @return Servo output 5 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field servo6_raw from servo_output_raw message - * - * @return Servo output 6 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field servo7_raw from servo_output_raw message - * - * @return Servo output 7 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field servo8_raw from servo_output_raw message - * - * @return Servo output 8 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Decode a servo_output_raw message into a struct - * - * @param msg The message to decode - * @param servo_output_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - servo_output_raw->time_usec = mavlink_msg_servo_output_raw_get_time_usec(msg); - servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg); - servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg); - servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg); - servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg); - servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg); - servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg); - servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN? msg->len : MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN; - memset(servo_output_raw, 0, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); - memcpy(servo_output_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_set_actuator_control_target.h b/include/mavlink/v1.0/common/mavlink_msg_set_actuator_control_target.h deleted file mode 100644 index f804d4b..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_set_actuator_control_target.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE SET_ACTUATOR_CONTROL_TARGET PACKING - -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET 139 - -MAVPACKED( -typedef struct __mavlink_set_actuator_control_target_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ - uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_set_actuator_control_target_t; - -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN 43 -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN 43 -#define MAVLINK_MSG_ID_139_LEN 43 -#define MAVLINK_MSG_ID_139_MIN_LEN 43 - -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC 168 -#define MAVLINK_MSG_ID_139_CRC 168 - -#define MAVLINK_MSG_SET_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET { \ - 139, \ - "SET_ACTUATOR_CONTROL_TARGET", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_set_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_set_actuator_control_target_t, group_mlx) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_set_actuator_control_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_actuator_control_target_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET { \ - "SET_ACTUATOR_CONTROL_TARGET", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_set_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_set_actuator_control_target_t, group_mlx) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_set_actuator_control_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_actuator_control_target_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_actuator_control_target 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 (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_set_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Pack a set_actuator_control_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t group_mlx,uint8_t target_system,uint8_t target_component,const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_set_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Encode a set_actuator_control_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ - return mavlink_msg_set_actuator_control_target_pack(system_id, component_id, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); -} - -/** - * @brief Encode a set_actuator_control_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ - return mavlink_msg_set_actuator_control_target_pack_chan(system_id, component_id, chan, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); -} - -/** - * @brief Send a set_actuator_control_target message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_set_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -/** - * @brief Send a set_actuator_control_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_actuator_control_target_send_struct(mavlink_channel_t chan, const mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_actuator_control_target_send(chan, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)set_actuator_control_target, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_set_actuator_control_target_t *packet = (mavlink_set_actuator_control_target_t *)msgbuf; - packet->time_usec = time_usec; - packet->group_mlx = group_mlx; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_ACTUATOR_CONTROL_TARGET UNPACKING - - -/** - * @brief Get field time_usec from set_actuator_control_target message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_set_actuator_control_target_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field group_mlx from set_actuator_control_target message - * - * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - */ -static inline uint8_t mavlink_msg_set_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field target_system from set_actuator_control_target message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Get field target_component from set_actuator_control_target message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field controls from set_actuator_control_target message - * - * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) -{ - return _MAV_RETURN_float_array(msg, controls, 8, 8); -} - -/** - * @brief Decode a set_actuator_control_target message into a struct - * - * @param msg The message to decode - * @param set_actuator_control_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_actuator_control_target->time_usec = mavlink_msg_set_actuator_control_target_get_time_usec(msg); - mavlink_msg_set_actuator_control_target_get_controls(msg, set_actuator_control_target->controls); - set_actuator_control_target->group_mlx = mavlink_msg_set_actuator_control_target_get_group_mlx(msg); - set_actuator_control_target->target_system = mavlink_msg_set_actuator_control_target_get_target_system(msg); - set_actuator_control_target->target_component = mavlink_msg_set_actuator_control_target_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN? msg->len : MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN; - memset(set_actuator_control_target, 0, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); - memcpy(set_actuator_control_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_set_attitude_target.h b/include/mavlink/v1.0/common/mavlink_msg_set_attitude_target.h deleted file mode 100644 index 1b68caa..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_set_attitude_target.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE SET_ATTITUDE_TARGET PACKING - -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET 82 - -MAVPACKED( -typedef struct __mavlink_set_attitude_target_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float body_roll_rate; /*< Body roll rate in radians per second*/ - float body_pitch_rate; /*< Body roll rate in radians per second*/ - float body_yaw_rate; /*< Body roll rate in radians per second*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude*/ -}) mavlink_set_attitude_target_t; - -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN 39 -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN 39 -#define MAVLINK_MSG_ID_82_LEN 39 -#define MAVLINK_MSG_ID_82_MIN_LEN 39 - -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC 49 -#define MAVLINK_MSG_ID_82_CRC 49 - -#define MAVLINK_MSG_SET_ATTITUDE_TARGET_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET { \ - 82, \ - "SET_ATTITUDE_TARGET", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET { \ - "SET_ATTITUDE_TARGET", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_attitude_target 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_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#else - mavlink_set_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Pack a set_attitude_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#else - mavlink_set_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Encode a set_attitude_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target) -{ - return mavlink_msg_set_attitude_target_pack(system_id, component_id, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust); -} - -/** - * @brief Encode a set_attitude_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target) -{ - return mavlink_msg_set_attitude_target_pack_chan(system_id, component_id, chan, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust); -} - -/** - * @brief Send a set_attitude_target message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#else - mavlink_set_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#endif -} - -/** - * @brief Send a set_attitude_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_attitude_target_send_struct(mavlink_channel_t chan, const mavlink_set_attitude_target_t* set_attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_attitude_target_send(chan, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)set_attitude_target, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#else - mavlink_set_attitude_target_t *packet = (mavlink_set_attitude_target_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->body_roll_rate = body_roll_rate; - packet->body_pitch_rate = body_pitch_rate; - packet->body_yaw_rate = body_yaw_rate; - packet->thrust = thrust; - packet->target_system = target_system; - packet->target_component = target_component; - packet->type_mask = type_mask; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_ATTITUDE_TARGET UNPACKING - - -/** - * @brief Get field time_boot_ms from set_attitude_target message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_set_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field target_system from set_attitude_target message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_attitude_target_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field target_component from set_attitude_target message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_attitude_target_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 37); -} - -/** - * @brief Get field type_mask from set_attitude_target message - * - * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - */ -static inline uint8_t mavlink_msg_set_attitude_target_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 38); -} - -/** - * @brief Get field q from set_attitude_target message - * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_set_attitude_target_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 4); -} - -/** - * @brief Get field body_roll_rate from set_attitude_target message - * - * @return Body roll rate in radians per second - */ -static inline float mavlink_msg_set_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field body_pitch_rate from set_attitude_target message - * - * @return Body roll rate in radians per second - */ -static inline float mavlink_msg_set_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field body_yaw_rate from set_attitude_target message - * - * @return Body roll rate in radians per second - */ -static inline float mavlink_msg_set_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field thrust from set_attitude_target message - * - * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - */ -static inline float mavlink_msg_set_attitude_target_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Decode a set_attitude_target message into a struct - * - * @param msg The message to decode - * @param set_attitude_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_attitude_target_decode(const mavlink_message_t* msg, mavlink_set_attitude_target_t* set_attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_attitude_target->time_boot_ms = mavlink_msg_set_attitude_target_get_time_boot_ms(msg); - mavlink_msg_set_attitude_target_get_q(msg, set_attitude_target->q); - set_attitude_target->body_roll_rate = mavlink_msg_set_attitude_target_get_body_roll_rate(msg); - set_attitude_target->body_pitch_rate = mavlink_msg_set_attitude_target_get_body_pitch_rate(msg); - set_attitude_target->body_yaw_rate = mavlink_msg_set_attitude_target_get_body_yaw_rate(msg); - set_attitude_target->thrust = mavlink_msg_set_attitude_target_get_thrust(msg); - set_attitude_target->target_system = mavlink_msg_set_attitude_target_get_target_system(msg); - set_attitude_target->target_component = mavlink_msg_set_attitude_target_get_target_component(msg); - set_attitude_target->type_mask = mavlink_msg_set_attitude_target_get_type_mask(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN? msg->len : MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN; - memset(set_attitude_target, 0, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); - memcpy(set_attitude_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h b/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h deleted file mode 100644 index a934c19..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE SET_GPS_GLOBAL_ORIGIN PACKING - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48 - -MAVPACKED( -typedef struct __mavlink_set_gps_global_origin_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ - uint8_t target_system; /*< System ID*/ -}) mavlink_set_gps_global_origin_t; - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13 -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN 13 -#define MAVLINK_MSG_ID_48_LEN 13 -#define MAVLINK_MSG_ID_48_MIN_LEN 13 - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC 41 -#define MAVLINK_MSG_ID_48_CRC 41 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ - 48, \ - "SET_GPS_GLOBAL_ORIGIN", \ - 4, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ - "SET_GPS_GLOBAL_ORIGIN", \ - 4, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_gps_global_origin message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), 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[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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - - 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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Pack a set_gps_global_origin message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @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, - 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[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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - - 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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Encode a set_gps_global_origin struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ - return mavlink_msg_set_gps_global_origin_pack(system_id, component_id, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); -} - -/** - * @brief Encode a set_gps_global_origin struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ - return mavlink_msg_set_gps_global_origin_pack_chan(system_id, component_id, chan, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); -} - -/** - * @brief Send a set_gps_global_origin message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - */ -#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[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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -/** - * @brief Send a set_gps_global_origin message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_gps_global_origin_send_struct(mavlink_channel_t chan, const mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_gps_global_origin_send(chan, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)set_gps_global_origin, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_gps_global_origin_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - mavlink_set_gps_global_origin_t *packet = (mavlink_set_gps_global_origin_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->target_system = target_system; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_GPS_GLOBAL_ORIGIN UNPACKING - - -/** - * @brief Get field target_system from set_gps_global_origin message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field latitude from set_gps_global_origin message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from set_gps_global_origin message - * - * @return Longitude (WGS84, in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from set_gps_global_origin message - * - * @return Altitude (AMSL), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Decode a set_gps_global_origin message into a struct - * - * @param msg The message to decode - * @param set_gps_global_origin C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_gps_global_origin->latitude = mavlink_msg_set_gps_global_origin_get_latitude(msg); - set_gps_global_origin->longitude = mavlink_msg_set_gps_global_origin_get_longitude(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN? msg->len : MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN; - memset(set_gps_global_origin, 0, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); - memcpy(set_gps_global_origin, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_set_home_position.h b/include/mavlink/v1.0/common/mavlink_msg_set_home_position.h deleted file mode 100644 index cd7c8d3..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_set_home_position.h +++ /dev/null @@ -1,455 +0,0 @@ -#pragma once -// MESSAGE SET_HOME_POSITION PACKING - -#define MAVLINK_MSG_ID_SET_HOME_POSITION 243 - -MAVPACKED( -typedef struct __mavlink_set_home_position_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ - float x; /*< Local X position of this position in the local coordinate frame*/ - float y; /*< Local Y position of this position in the local coordinate frame*/ - float z; /*< Local Z position of this position in the local coordinate frame*/ - float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ - float approach_x; /*< Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_y; /*< Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_z; /*< Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - uint8_t target_system; /*< System ID.*/ -}) mavlink_set_home_position_t; - -#define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN 53 -#define MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN 53 -#define MAVLINK_MSG_ID_243_LEN 53 -#define MAVLINK_MSG_ID_243_MIN_LEN 53 - -#define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC 85 -#define MAVLINK_MSG_ID_243_CRC 85 - -#define MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \ - 243, \ - "SET_HOME_POSITION", \ - 11, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \ - "SET_HOME_POSITION", \ - 11, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_home_position message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID. - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#else - mavlink_set_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.target_system = target_system; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -} - -/** - * @brief Pack a set_home_position message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID. - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#else - mavlink_set_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.target_system = target_system; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -} - -/** - * @brief Encode a set_home_position struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position) -{ - return mavlink_msg_set_home_position_pack(system_id, component_id, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z); -} - -/** - * @brief Encode a set_home_position struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position) -{ - return mavlink_msg_set_home_position_pack_chan(system_id, component_id, chan, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z); -} - -/** - * @brief Send a set_home_position message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID. - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_home_position_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#else - mavlink_set_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.target_system = target_system; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#endif -} - -/** - * @brief Send a set_home_position message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_home_position_send_struct(mavlink_channel_t chan, const mavlink_set_home_position_t* set_home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_home_position_send(chan, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)set_home_position, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#else - mavlink_set_home_position_t *packet = (mavlink_set_home_position_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->x = x; - packet->y = y; - packet->z = z; - packet->approach_x = approach_x; - packet->approach_y = approach_y; - packet->approach_z = approach_z; - packet->target_system = target_system; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_HOME_POSITION UNPACKING - - -/** - * @brief Get field target_system from set_home_position message - * - * @return System ID. - */ -static inline uint8_t mavlink_msg_set_home_position_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field latitude from set_home_position message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_home_position_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from set_home_position message - * - * @return Longitude (WGS84, in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_home_position_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from set_home_position message - * - * @return Altitude (AMSL), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_set_home_position_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field x from set_home_position message - * - * @return Local X position of this position in the local coordinate frame - */ -static inline float mavlink_msg_set_home_position_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field y from set_home_position message - * - * @return Local Y position of this position in the local coordinate frame - */ -static inline float mavlink_msg_set_home_position_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field z from set_home_position message - * - * @return Local Z position of this position in the local coordinate frame - */ -static inline float mavlink_msg_set_home_position_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field q from set_home_position message - * - * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - */ -static inline uint16_t mavlink_msg_set_home_position_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 24); -} - -/** - * @brief Get field approach_x from set_home_position message - * - * @return Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_set_home_position_get_approach_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field approach_y from set_home_position message - * - * @return Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_set_home_position_get_approach_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field approach_z from set_home_position message - * - * @return Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_set_home_position_get_approach_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Decode a set_home_position message into a struct - * - * @param msg The message to decode - * @param set_home_position C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_home_position_decode(const mavlink_message_t* msg, mavlink_set_home_position_t* set_home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_home_position->latitude = mavlink_msg_set_home_position_get_latitude(msg); - set_home_position->longitude = mavlink_msg_set_home_position_get_longitude(msg); - set_home_position->altitude = mavlink_msg_set_home_position_get_altitude(msg); - set_home_position->x = mavlink_msg_set_home_position_get_x(msg); - set_home_position->y = mavlink_msg_set_home_position_get_y(msg); - set_home_position->z = mavlink_msg_set_home_position_get_z(msg); - mavlink_msg_set_home_position_get_q(msg, set_home_position->q); - set_home_position->approach_x = mavlink_msg_set_home_position_get_approach_x(msg); - set_home_position->approach_y = mavlink_msg_set_home_position_get_approach_y(msg); - set_home_position->approach_z = mavlink_msg_set_home_position_get_approach_z(msg); - set_home_position->target_system = mavlink_msg_set_home_position_get_target_system(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_HOME_POSITION_LEN? msg->len : MAVLINK_MSG_ID_SET_HOME_POSITION_LEN; - memset(set_home_position, 0, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); - memcpy(set_home_position, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_set_mode.h b/include/mavlink/v1.0/common/mavlink_msg_set_mode.h deleted file mode 100644 index a4c6ef3..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_set_mode.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE SET_MODE PACKING - -#define MAVLINK_MSG_ID_SET_MODE 11 - -MAVPACKED( -typedef struct __mavlink_set_mode_t { - uint32_t custom_mode; /*< The new autopilot-specific mode. This field can be ignored by an autopilot.*/ - uint8_t target_system; /*< The system setting the mode*/ - uint8_t base_mode; /*< The new base mode*/ -}) mavlink_set_mode_t; - -#define MAVLINK_MSG_ID_SET_MODE_LEN 6 -#define MAVLINK_MSG_ID_SET_MODE_MIN_LEN 6 -#define MAVLINK_MSG_ID_11_LEN 6 -#define MAVLINK_MSG_ID_11_MIN_LEN 6 - -#define MAVLINK_MSG_ID_SET_MODE_CRC 89 -#define MAVLINK_MSG_ID_11_CRC 89 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_MODE { \ - 11, \ - "SET_MODE", \ - 3, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_MODE { \ - "SET_MODE", \ - 3, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_mode message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_MODE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -} - -/** - * @brief Pack a set_mode message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t base_mode,uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -} - -/** - * @brief Encode a set_mode struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_mode C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) -{ - return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); -} - -/** - * @brief Encode a set_mode struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_mode C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_mode_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) -{ - return mavlink_msg_set_mode_pack_chan(system_id, component_id, chan, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); -} - -/** - * @brief Send a set_mode message - * @param chan MAVLink channel to send the message - * - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#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, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#endif -} - -/** - * @brief Send a set_mode message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_mode_send_struct(mavlink_channel_t chan, const mavlink_set_mode_t* set_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_mode_send(chan, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)set_mode, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_MODE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_mode_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#else - mavlink_set_mode_t *packet = (mavlink_set_mode_t *)msgbuf; - 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, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_MODE UNPACKING - - -/** - * @brief Get field target_system from set_mode message - * - * @return The system setting the mode - */ -static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field base_mode from set_mode message - * - * @return The new base mode - */ -static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field custom_mode from set_mode message - * - * @return The new autopilot-specific mode. This field can be ignored by an autopilot. - */ -static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Decode a set_mode message into a struct - * - * @param msg The message to decode - * @param set_mode C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_mode->custom_mode = mavlink_msg_set_mode_get_custom_mode(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_MODE_LEN? msg->len : MAVLINK_MSG_ID_SET_MODE_LEN; - memset(set_mode, 0, MAVLINK_MSG_ID_SET_MODE_LEN); - memcpy(set_mode, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_set_position_target_global_int.h b/include/mavlink/v1.0/common/mavlink_msg_set_position_target_global_int.h deleted file mode 100644 index ec0c9c1..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_set_position_target_global_int.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE SET_POSITION_TARGET_GLOBAL_INT PACKING - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT 86 - -MAVPACKED( -typedef struct __mavlink_set_position_target_global_int_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ - int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/ - int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/ - float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ -}) mavlink_set_position_target_global_int_t; - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53 -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN 53 -#define MAVLINK_MSG_ID_86_LEN 53 -#define MAVLINK_MSG_ID_86_MIN_LEN 53 - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 5 -#define MAVLINK_MSG_ID_86_CRC 5 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \ - 86, \ - "SET_POSITION_TARGET_GLOBAL_INT", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \ - "SET_POSITION_TARGET_GLOBAL_INT", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_position_target_global_int 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_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_set_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Pack a set_position_target_global_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_set_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Encode a set_position_target_global_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ - return mavlink_msg_set_position_target_global_int_pack(system_id, component_id, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); -} - -/** - * @brief Encode a set_position_target_global_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ - return mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, chan, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); -} - -/** - * @brief Send a set_position_target_global_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_set_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -/** - * @brief Send a set_position_target_global_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_position_target_global_int_send_struct(mavlink_channel_t chan, const mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_position_target_global_int_send(chan, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)set_position_target_global_int, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_set_position_target_global_int_t *packet = (mavlink_set_position_target_global_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->lat_int = lat_int; - packet->lon_int = lon_int; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->target_system = target_system; - packet->target_component = target_component; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_POSITION_TARGET_GLOBAL_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from set_position_target_global_int message - * - * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - */ -static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field target_system from set_position_target_global_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field target_component from set_position_target_global_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 51); -} - -/** - * @brief Get field coordinate_frame from set_position_target_global_int message - * - * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - */ -static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field type_mask from set_position_target_global_int message - * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field lat_int from set_position_target_global_int message - * - * @return X Position in WGS84 frame in 1e7 * meters - */ -static inline int32_t mavlink_msg_set_position_target_global_int_get_lat_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon_int from set_position_target_global_int message - * - * @return Y Position in WGS84 frame in 1e7 * meters - */ -static inline int32_t mavlink_msg_set_position_target_global_int_get_lon_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt from set_position_target_global_int message - * - * @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - */ -static inline float mavlink_msg_set_position_target_global_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from set_position_target_global_int message - * - * @return X velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_global_int_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from set_position_target_global_int message - * - * @return Y velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_global_int_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from set_position_target_global_int message - * - * @return Z velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_global_int_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from set_position_target_global_int message - * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_global_int_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from set_position_target_global_int message - * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_global_int_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from set_position_target_global_int message - * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_global_int_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from set_position_target_global_int message - * - * @return yaw setpoint in rad - */ -static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from set_position_target_global_int message - * - * @return yaw rate setpoint in rad/s - */ -static inline float mavlink_msg_set_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a set_position_target_global_int message into a struct - * - * @param msg The message to decode - * @param set_position_target_global_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_position_target_global_int->time_boot_ms = mavlink_msg_set_position_target_global_int_get_time_boot_ms(msg); - set_position_target_global_int->lat_int = mavlink_msg_set_position_target_global_int_get_lat_int(msg); - set_position_target_global_int->lon_int = mavlink_msg_set_position_target_global_int_get_lon_int(msg); - set_position_target_global_int->alt = mavlink_msg_set_position_target_global_int_get_alt(msg); - set_position_target_global_int->vx = mavlink_msg_set_position_target_global_int_get_vx(msg); - set_position_target_global_int->vy = mavlink_msg_set_position_target_global_int_get_vy(msg); - set_position_target_global_int->vz = mavlink_msg_set_position_target_global_int_get_vz(msg); - set_position_target_global_int->afx = mavlink_msg_set_position_target_global_int_get_afx(msg); - set_position_target_global_int->afy = mavlink_msg_set_position_target_global_int_get_afy(msg); - set_position_target_global_int->afz = mavlink_msg_set_position_target_global_int_get_afz(msg); - set_position_target_global_int->yaw = mavlink_msg_set_position_target_global_int_get_yaw(msg); - set_position_target_global_int->yaw_rate = mavlink_msg_set_position_target_global_int_get_yaw_rate(msg); - set_position_target_global_int->type_mask = mavlink_msg_set_position_target_global_int_get_type_mask(msg); - set_position_target_global_int->target_system = mavlink_msg_set_position_target_global_int_get_target_system(msg); - set_position_target_global_int->target_component = mavlink_msg_set_position_target_global_int_get_target_component(msg); - set_position_target_global_int->coordinate_frame = mavlink_msg_set_position_target_global_int_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN? msg->len : MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN; - memset(set_position_target_global_int, 0, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); - memcpy(set_position_target_global_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_set_position_target_local_ned.h b/include/mavlink/v1.0/common/mavlink_msg_set_position_target_local_ned.h deleted file mode 100644 index af4e8d6..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_set_position_target_local_ned.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE SET_POSITION_TARGET_LOCAL_NED PACKING - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED 84 - -MAVPACKED( -typedef struct __mavlink_set_position_target_local_ned_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float x; /*< X Position in NED frame in meters*/ - float y; /*< Y Position in NED frame in meters*/ - float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ -}) mavlink_set_position_target_local_ned_t; - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53 -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN 53 -#define MAVLINK_MSG_ID_84_LEN 53 -#define MAVLINK_MSG_ID_84_MIN_LEN 53 - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 143 -#define MAVLINK_MSG_ID_84_CRC 143 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \ - 84, \ - "SET_POSITION_TARGET_LOCAL_NED", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \ - "SET_POSITION_TARGET_LOCAL_NED", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_position_target_local_ned 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_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_set_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Pack a set_position_target_local_ned message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_set_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Encode a set_position_target_local_ned struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ - return mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); -} - -/** - * @brief Encode a set_position_target_local_ned struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ - return mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); -} - -/** - * @brief Send a set_position_target_local_ned message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_set_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -/** - * @brief Send a set_position_target_local_ned message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_position_target_local_ned_send_struct(mavlink_channel_t chan, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_position_target_local_ned_send(chan, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)set_position_target_local_ned, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_set_position_target_local_ned_t *packet = (mavlink_set_position_target_local_ned_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->target_system = target_system; - packet->target_component = target_component; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_POSITION_TARGET_LOCAL_NED UNPACKING - - -/** - * @brief Get field time_boot_ms from set_position_target_local_ned message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_set_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field target_system from set_position_target_local_ned message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field target_component from set_position_target_local_ned message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 51); -} - -/** - * @brief Get field coordinate_frame from set_position_target_local_ned message - * - * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - */ -static inline uint8_t mavlink_msg_set_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field type_mask from set_position_target_local_ned message - * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field x from set_position_target_local_ned message - * - * @return X Position in NED frame in meters - */ -static inline float mavlink_msg_set_position_target_local_ned_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from set_position_target_local_ned message - * - * @return Y Position in NED frame in meters - */ -static inline float mavlink_msg_set_position_target_local_ned_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from set_position_target_local_ned message - * - * @return Z Position in NED frame in meters (note, altitude is negative in NED) - */ -static inline float mavlink_msg_set_position_target_local_ned_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from set_position_target_local_ned message - * - * @return X velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_local_ned_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from set_position_target_local_ned message - * - * @return Y velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_local_ned_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from set_position_target_local_ned message - * - * @return Z velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_local_ned_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from set_position_target_local_ned message - * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_local_ned_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from set_position_target_local_ned message - * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_local_ned_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from set_position_target_local_ned message - * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_local_ned_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from set_position_target_local_ned message - * - * @return yaw setpoint in rad - */ -static inline float mavlink_msg_set_position_target_local_ned_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from set_position_target_local_ned message - * - * @return yaw rate setpoint in rad/s - */ -static inline float mavlink_msg_set_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a set_position_target_local_ned message into a struct - * - * @param msg The message to decode - * @param set_position_target_local_ned C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_position_target_local_ned->time_boot_ms = mavlink_msg_set_position_target_local_ned_get_time_boot_ms(msg); - set_position_target_local_ned->x = mavlink_msg_set_position_target_local_ned_get_x(msg); - set_position_target_local_ned->y = mavlink_msg_set_position_target_local_ned_get_y(msg); - set_position_target_local_ned->z = mavlink_msg_set_position_target_local_ned_get_z(msg); - set_position_target_local_ned->vx = mavlink_msg_set_position_target_local_ned_get_vx(msg); - set_position_target_local_ned->vy = mavlink_msg_set_position_target_local_ned_get_vy(msg); - set_position_target_local_ned->vz = mavlink_msg_set_position_target_local_ned_get_vz(msg); - set_position_target_local_ned->afx = mavlink_msg_set_position_target_local_ned_get_afx(msg); - set_position_target_local_ned->afy = mavlink_msg_set_position_target_local_ned_get_afy(msg); - set_position_target_local_ned->afz = mavlink_msg_set_position_target_local_ned_get_afz(msg); - set_position_target_local_ned->yaw = mavlink_msg_set_position_target_local_ned_get_yaw(msg); - set_position_target_local_ned->yaw_rate = mavlink_msg_set_position_target_local_ned_get_yaw_rate(msg); - set_position_target_local_ned->type_mask = mavlink_msg_set_position_target_local_ned_get_type_mask(msg); - set_position_target_local_ned->target_system = mavlink_msg_set_position_target_local_ned_get_target_system(msg); - set_position_target_local_ned->target_component = mavlink_msg_set_position_target_local_ned_get_target_component(msg); - set_position_target_local_ned->coordinate_frame = mavlink_msg_set_position_target_local_ned_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN? msg->len : MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN; - memset(set_position_target_local_ned, 0, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); - memcpy(set_position_target_local_ned, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_sim_state.h b/include/mavlink/v1.0/common/mavlink_msg_sim_state.h deleted file mode 100644 index e49a07f..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_sim_state.h +++ /dev/null @@ -1,713 +0,0 @@ -#pragma once -// MESSAGE SIM_STATE PACKING - -#define MAVLINK_MSG_ID_SIM_STATE 108 - -MAVPACKED( -typedef struct __mavlink_sim_state_t { - float q1; /*< True attitude quaternion component 1, w (1 in null-rotation)*/ - float q2; /*< True attitude quaternion component 2, x (0 in null-rotation)*/ - float q3; /*< True attitude quaternion component 3, y (0 in null-rotation)*/ - float q4; /*< True attitude quaternion component 4, z (0 in null-rotation)*/ - float roll; /*< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs*/ - float pitch; /*< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs*/ - float yaw; /*< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs*/ - float xacc; /*< X acceleration m/s/s*/ - float yacc; /*< Y acceleration m/s/s*/ - float zacc; /*< Z acceleration m/s/s*/ - float xgyro; /*< Angular speed around X axis rad/s*/ - float ygyro; /*< Angular speed around Y axis rad/s*/ - float zgyro; /*< Angular speed around Z axis rad/s*/ - float lat; /*< Latitude in degrees*/ - float lon; /*< Longitude in degrees*/ - float alt; /*< Altitude in meters*/ - float std_dev_horz; /*< Horizontal position standard deviation*/ - float std_dev_vert; /*< Vertical position standard deviation*/ - float vn; /*< True velocity in m/s in NORTH direction in earth-fixed NED frame*/ - float ve; /*< True velocity in m/s in EAST direction in earth-fixed NED frame*/ - float vd; /*< True velocity in m/s in DOWN direction in earth-fixed NED frame*/ -}) mavlink_sim_state_t; - -#define MAVLINK_MSG_ID_SIM_STATE_LEN 84 -#define MAVLINK_MSG_ID_SIM_STATE_MIN_LEN 84 -#define MAVLINK_MSG_ID_108_LEN 84 -#define MAVLINK_MSG_ID_108_MIN_LEN 84 - -#define MAVLINK_MSG_ID_SIM_STATE_CRC 32 -#define MAVLINK_MSG_ID_108_CRC 32 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SIM_STATE { \ - 108, \ - "SIM_STATE", \ - 21, \ - { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \ - { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \ - { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \ - { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SIM_STATE { \ - "SIM_STATE", \ - 21, \ - { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \ - { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \ - { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \ - { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \ - } \ -} -#endif - -/** - * @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 q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame - * @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 q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _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, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - 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.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SIM_STATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -} - -/** - * @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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame - * @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 q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _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, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - 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.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SIM_STATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -} - -/** - * @brief Encode a sim_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param 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->q1, sim_state->q2, sim_state->q3, sim_state->q4, 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->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); -} - -/** - * @brief Encode a sim_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sim_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sim_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state) -{ - return mavlink_msg_sim_state_pack_chan(system_id, component_id, chan, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, 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->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); -} - -/** - * @brief Send a sim_state message - * @param chan MAVLink channel to send the message - * - * @param q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_sim_state_send(mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _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, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - 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.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#endif -} - -/** - * @brief Send a sim_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_sim_state_send_struct(mavlink_channel_t chan, const mavlink_sim_state_t* sim_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_sim_state_send(chan, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, 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->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)sim_state, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SIM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_sim_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _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, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - mavlink_sim_state_t *packet = (mavlink_sim_state_t *)msgbuf; - packet->q1 = q1; - packet->q2 = q2; - packet->q3 = q3; - packet->q4 = q4; - 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->lon = lon; - packet->alt = alt; - packet->std_dev_horz = std_dev_horz; - packet->std_dev_vert = std_dev_vert; - packet->vn = vn; - packet->ve = ve; - packet->vd = vd; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SIM_STATE UNPACKING - - -/** - * @brief Get field q1 from sim_state message - * - * @return True attitude quaternion component 1, w (1 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field q2 from sim_state message - * - * @return True attitude quaternion component 2, x (0 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field q3 from sim_state message - * - * @return True attitude quaternion component 3, y (0 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field q4 from sim_state message - * - * @return True attitude quaternion component 4, z (0 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field roll from sim_state message - * - * @return Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitch from sim_state message - * - * @return Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yaw from sim_state message - * - * @return Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @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, 28); -} - -/** - * @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, 32); -} - -/** - * @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, 36); -} - -/** - * @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, 40); -} - -/** - * @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, 44); -} - -/** - * @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, 48); -} - -/** - * @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, 52); -} - -/** - * @brief Get field lon from sim_state message - * - * @return Longitude in degrees - */ -static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field alt from sim_state message - * - * @return Altitude in meters - */ -static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 60); -} - -/** - * @brief Get field std_dev_horz from sim_state message - * - * @return Horizontal position standard deviation - */ -static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 64); -} - -/** - * @brief Get field std_dev_vert from sim_state message - * - * @return Vertical position standard deviation - */ -static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 68); -} - -/** - * @brief Get field vn from sim_state message - * - * @return True velocity in m/s in NORTH direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 72); -} - -/** - * @brief Get field ve from sim_state message - * - * @return True velocity in m/s in EAST direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 76); -} - -/** - * @brief Get field vd from sim_state message - * - * @return True velocity in m/s in DOWN direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_vd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 80); -} - -/** - * @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 || !MAVLINK_ALIGNED_FIELDS - sim_state->q1 = mavlink_msg_sim_state_get_q1(msg); - sim_state->q2 = mavlink_msg_sim_state_get_q2(msg); - sim_state->q3 = mavlink_msg_sim_state_get_q3(msg); - sim_state->q4 = mavlink_msg_sim_state_get_q4(msg); - 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->lon = mavlink_msg_sim_state_get_lon(msg); - sim_state->alt = mavlink_msg_sim_state_get_alt(msg); - sim_state->std_dev_horz = mavlink_msg_sim_state_get_std_dev_horz(msg); - sim_state->std_dev_vert = mavlink_msg_sim_state_get_std_dev_vert(msg); - sim_state->vn = mavlink_msg_sim_state_get_vn(msg); - sim_state->ve = mavlink_msg_sim_state_get_ve(msg); - sim_state->vd = mavlink_msg_sim_state_get_vd(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SIM_STATE_LEN? msg->len : MAVLINK_MSG_ID_SIM_STATE_LEN; - memset(sim_state, 0, MAVLINK_MSG_ID_SIM_STATE_LEN); - memcpy(sim_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_statustext.h b/include/mavlink/v1.0/common/mavlink_msg_statustext.h deleted file mode 100644 index e1ed320..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_statustext.h +++ /dev/null @@ -1,230 +0,0 @@ -#pragma once -// MESSAGE STATUSTEXT PACKING - -#define MAVLINK_MSG_ID_STATUSTEXT 253 - -MAVPACKED( -typedef struct __mavlink_statustext_t { - uint8_t severity; /*< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.*/ - char text[50]; /*< Status text message, without null termination character*/ -}) mavlink_statustext_t; - -#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51 -#define MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN 51 -#define MAVLINK_MSG_ID_253_LEN 51 -#define MAVLINK_MSG_ID_253_MIN_LEN 51 - -#define MAVLINK_MSG_ID_STATUSTEXT_CRC 83 -#define MAVLINK_MSG_ID_253_CRC 83 - -#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ - 253, \ - "STATUSTEXT", \ - 2, \ - { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ - { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ - "STATUSTEXT", \ - 2, \ - { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ - { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \ - } \ -} -#endif - -/** - * @brief Pack a statustext 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 severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t severity, const char *text) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -} - -/** - * @brief Pack a statustext message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t severity,const char *text) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -} - -/** - * @brief Encode a statustext struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param statustext C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext) -{ - return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text); -} - -/** - * @brief Encode a statustext struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param statustext C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_statustext_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_statustext_t* statustext) -{ - return mavlink_msg_statustext_pack_chan(system_id, component_id, chan, msg, statustext->severity, statustext->text); -} - -/** - * @brief Send a statustext message - * @param chan MAVLink channel to send the message - * - * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#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, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#endif -} - -/** - * @brief Send a statustext message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_statustext_send_struct(mavlink_channel_t chan, const mavlink_statustext_t* statustext) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_statustext_send(chan, statustext->severity, statustext->text); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)statustext, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_STATUSTEXT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_statustext_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t severity, const char *text) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#else - mavlink_statustext_t *packet = (mavlink_statustext_t *)msgbuf; - 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, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE STATUSTEXT UNPACKING - - -/** - * @brief Get field severity from statustext message - * - * @return Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - */ -static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field text from statustext message - * - * @return Status text message, without null termination character - */ -static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text) -{ - return _MAV_RETURN_char_array(msg, text, 50, 1); -} - -/** - * @brief Decode a statustext message into a struct - * - * @param msg The message to decode - * @param statustext C-struct to decode the message contents into - */ -static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - statustext->severity = mavlink_msg_statustext_get_severity(msg); - mavlink_msg_statustext_get_text(msg, statustext->text); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_STATUSTEXT_LEN? msg->len : MAVLINK_MSG_ID_STATUSTEXT_LEN; - memset(statustext, 0, MAVLINK_MSG_ID_STATUSTEXT_LEN); - memcpy(statustext, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_sys_status.h b/include/mavlink/v1.0/common/mavlink_msg_sys_status.h deleted file mode 100644 index 28a85b5..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_sys_status.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE SYS_STATUS PACKING - -#define MAVLINK_MSG_ID_SYS_STATUS 1 - -MAVPACKED( -typedef struct __mavlink_sys_status_t { - uint32_t onboard_control_sensors_present; /*< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ - uint32_t onboard_control_sensors_enabled; /*< Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ - uint32_t onboard_control_sensors_health; /*< Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ - uint16_t load; /*< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000*/ - uint16_t voltage_battery; /*< Battery voltage, in millivolts (1 = 1 millivolt)*/ - int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/ - uint16_t drop_rate_comm; /*< Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ - uint16_t errors_comm; /*< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ - uint16_t errors_count1; /*< Autopilot-specific errors*/ - uint16_t errors_count2; /*< Autopilot-specific errors*/ - uint16_t errors_count3; /*< Autopilot-specific errors*/ - uint16_t errors_count4; /*< Autopilot-specific errors*/ - int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery*/ -}) mavlink_sys_status_t; - -#define MAVLINK_MSG_ID_SYS_STATUS_LEN 31 -#define MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN 31 -#define MAVLINK_MSG_ID_1_LEN 31 -#define MAVLINK_MSG_ID_1_MIN_LEN 31 - -#define MAVLINK_MSG_ID_SYS_STATUS_CRC 124 -#define MAVLINK_MSG_ID_1_CRC 124 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ - 1, \ - "SYS_STATUS", \ - 13, \ - { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \ - { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \ - { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \ - { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ - { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ - { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ - { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ - { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ - { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ - { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ - { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ - "SYS_STATUS", \ - 13, \ - { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \ - { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \ - { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \ - { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ - { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ - { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ - { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ - { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ - { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ - { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ - { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ - } \ -} -#endif - -/** - * @brief Pack a sys_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - - 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; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - - 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, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -} - -/** - * @brief Pack a sys_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - - 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; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - - 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, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -} - -/** - * @brief Encode a sys_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param sys_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) -{ - return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); -} - -/** - * @brief Encode a sys_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sys_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sys_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) -{ - return mavlink_msg_sys_status_pack_chan(system_id, component_id, chan, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); -} - -/** - * @brief Send a sys_status message - * @param chan MAVLink channel to send the message - * - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _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, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - mavlink_sys_status_t packet; - packet.onboard_control_sensors_present = onboard_control_sensors_present; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#endif -} - -/** - * @brief Send a sys_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_sys_status_send_struct(mavlink_channel_t chan, const mavlink_sys_status_t* sys_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_sys_status_send(chan, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)sys_status, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SYS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_sys_status_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _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, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - mavlink_sys_status_t *packet = (mavlink_sys_status_t *)msgbuf; - packet->onboard_control_sensors_present = onboard_control_sensors_present; - packet->onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet->onboard_control_sensors_health = onboard_control_sensors_health; - packet->load = load; - packet->voltage_battery = voltage_battery; - packet->current_battery = current_battery; - packet->drop_rate_comm = drop_rate_comm; - packet->errors_comm = errors_comm; - packet->errors_count1 = errors_count1; - packet->errors_count2 = errors_count2; - packet->errors_count3 = errors_count3; - packet->errors_count4 = errors_count4; - packet->battery_remaining = battery_remaining; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SYS_STATUS UNPACKING - - -/** - * @brief Get field onboard_control_sensors_present from sys_status message - * - * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field onboard_control_sensors_enabled from sys_status message - * - * @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field onboard_control_sensors_health from sys_status message - * - * @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field load from sys_status message - * - * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - */ -static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field voltage_battery from sys_status message - * - * @return Battery voltage, in millivolts (1 = 1 millivolt) - */ -static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field current_battery from sys_status message - * - * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - */ -static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field battery_remaining from sys_status message - * - * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - */ -static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 30); -} - -/** - * @brief Get field drop_rate_comm from sys_status message - * - * @return Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - */ -static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field errors_comm from sys_status message - * - * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field errors_count1 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field errors_count2 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field errors_count3 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field errors_count4 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Decode a sys_status message into a struct - * - * @param msg The message to decode - * @param sys_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg); - sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg); - sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg); - sys_status->load = mavlink_msg_sys_status_get_load(msg); - sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg); - sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg); - sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg); - sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg); - sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg); - sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg); - sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SYS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_SYS_STATUS_LEN; - memset(sys_status, 0, MAVLINK_MSG_ID_SYS_STATUS_LEN); - memcpy(sys_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_system_time.h b/include/mavlink/v1.0/common/mavlink_msg_system_time.h deleted file mode 100644 index 0e9b2ce..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_system_time.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE SYSTEM_TIME PACKING - -#define MAVLINK_MSG_ID_SYSTEM_TIME 2 - -MAVPACKED( -typedef struct __mavlink_system_time_t { - uint64_t time_unix_usec; /*< Timestamp of the master clock in microseconds since UNIX epoch.*/ - uint32_t time_boot_ms; /*< Timestamp of the component clock since boot time in milliseconds.*/ -}) mavlink_system_time_t; - -#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 -#define MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN 12 -#define MAVLINK_MSG_ID_2_LEN 12 -#define MAVLINK_MSG_ID_2_MIN_LEN 12 - -#define MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137 -#define MAVLINK_MSG_ID_2_CRC 137 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ - 2, \ - "SYSTEM_TIME", \ - 2, \ - { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ - "SYSTEM_TIME", \ - 2, \ - { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \ - } \ -} -#endif - -/** - * @brief Pack a system_time 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_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_unix_usec, uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -} - -/** - * @brief Pack a system_time message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_unix_usec,uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -} - -/** - * @brief Encode a system_time struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param system_time C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time) -{ - return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms); -} - -/** - * @brief Encode a system_time struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param system_time C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_system_time_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_system_time_t* system_time) -{ - return mavlink_msg_system_time_pack_chan(system_id, component_id, chan, msg, system_time->time_unix_usec, system_time->time_boot_ms); -} - -/** - * @brief Send a system_time message - * @param chan MAVLink channel to send the message - * - * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#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, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#endif -} - -/** - * @brief Send a system_time message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_system_time_send_struct(mavlink_channel_t chan, const mavlink_system_time_t* system_time) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_system_time_send(chan, system_time->time_unix_usec, system_time->time_boot_ms); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)system_time, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SYSTEM_TIME_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_system_time_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#else - mavlink_system_time_t *packet = (mavlink_system_time_t *)msgbuf; - 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, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SYSTEM_TIME UNPACKING - - -/** - * @brief Get field time_unix_usec from system_time message - * - * @return Timestamp of the master clock in microseconds since UNIX epoch. - */ -static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field time_boot_ms from system_time message - * - * @return Timestamp of the component clock since boot time in milliseconds. - */ -static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Decode a system_time message into a struct - * - * @param msg The message to decode - * @param system_time C-struct to decode the message contents into - */ -static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SYSTEM_TIME_LEN? msg->len : MAVLINK_MSG_ID_SYSTEM_TIME_LEN; - memset(system_time, 0, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); - memcpy(system_time, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_terrain_check.h b/include/mavlink/v1.0/common/mavlink_msg_terrain_check.h deleted file mode 100644 index 820ff33..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_terrain_check.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_CHECK PACKING - -#define MAVLINK_MSG_ID_TERRAIN_CHECK 135 - -MAVPACKED( -typedef struct __mavlink_terrain_check_t { - int32_t lat; /*< Latitude (degrees *10^7)*/ - int32_t lon; /*< Longitude (degrees *10^7)*/ -}) mavlink_terrain_check_t; - -#define MAVLINK_MSG_ID_TERRAIN_CHECK_LEN 8 -#define MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN 8 -#define MAVLINK_MSG_ID_135_LEN 8 -#define MAVLINK_MSG_ID_135_MIN_LEN 8 - -#define MAVLINK_MSG_ID_TERRAIN_CHECK_CRC 203 -#define MAVLINK_MSG_ID_135_CRC 203 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_CHECK { \ - 135, \ - "TERRAIN_CHECK", \ - 2, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_check_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_check_t, lon) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_CHECK { \ - "TERRAIN_CHECK", \ - 2, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_check_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_check_t, lon) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_check 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 lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_check_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#else - mavlink_terrain_check_t packet; - packet.lat = lat; - packet.lon = lon; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -} - -/** - * @brief Pack a terrain_check message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_check_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#else - mavlink_terrain_check_t packet; - packet.lat = lat; - packet.lon = lon; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -} - -/** - * @brief Encode a terrain_check struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_check C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_check_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check) -{ - return mavlink_msg_terrain_check_pack(system_id, component_id, msg, terrain_check->lat, terrain_check->lon); -} - -/** - * @brief Encode a terrain_check struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_check C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_check_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check) -{ - return mavlink_msg_terrain_check_pack_chan(system_id, component_id, chan, msg, terrain_check->lat, terrain_check->lon); -} - -/** - * @brief Send a terrain_check message - * @param chan MAVLink channel to send the message - * - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_check_send(mavlink_channel_t chan, int32_t lat, int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#else - mavlink_terrain_check_t packet; - packet.lat = lat; - packet.lon = lon; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#endif -} - -/** - * @brief Send a terrain_check message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_check_send_struct(mavlink_channel_t chan, const mavlink_terrain_check_t* terrain_check) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_check_send(chan, terrain_check->lat, terrain_check->lon); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)terrain_check, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_CHECK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_check_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#else - mavlink_terrain_check_t *packet = (mavlink_terrain_check_t *)msgbuf; - packet->lat = lat; - packet->lon = lon; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_CHECK UNPACKING - - -/** - * @brief Get field lat from terrain_check message - * - * @return Latitude (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_check_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lon from terrain_check message - * - * @return Longitude (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_check_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Decode a terrain_check message into a struct - * - * @param msg The message to decode - * @param terrain_check C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_check_decode(const mavlink_message_t* msg, mavlink_terrain_check_t* terrain_check) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_check->lat = mavlink_msg_terrain_check_get_lat(msg); - terrain_check->lon = mavlink_msg_terrain_check_get_lon(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_CHECK_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_CHECK_LEN; - memset(terrain_check, 0, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); - memcpy(terrain_check, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_terrain_data.h b/include/mavlink/v1.0/common/mavlink_msg_terrain_data.h deleted file mode 100644 index ac9b9be..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_terrain_data.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_DATA PACKING - -#define MAVLINK_MSG_ID_TERRAIN_DATA 134 - -MAVPACKED( -typedef struct __mavlink_terrain_data_t { - int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/ - int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/ - uint16_t grid_spacing; /*< Grid spacing in meters*/ - int16_t data[16]; /*< Terrain data in meters AMSL*/ - uint8_t gridbit; /*< bit within the terrain request mask*/ -}) mavlink_terrain_data_t; - -#define MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43 -#define MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN 43 -#define MAVLINK_MSG_ID_134_LEN 43 -#define MAVLINK_MSG_ID_134_MIN_LEN 43 - -#define MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229 -#define MAVLINK_MSG_ID_134_CRC 229 - -#define MAVLINK_MSG_TERRAIN_DATA_FIELD_DATA_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \ - 134, \ - "TERRAIN_DATA", \ - 5, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \ - { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ - { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \ - "TERRAIN_DATA", \ - 5, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \ - { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ - { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_data 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 lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param gridbit bit within the terrain request mask - * @param data Terrain data in meters AMSL - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#else - mavlink_terrain_data_t packet; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - packet.gridbit = gridbit; - mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -} - -/** - * @brief Pack a terrain_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param gridbit bit within the terrain request mask - * @param data Terrain data in meters AMSL - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon,uint16_t grid_spacing,uint8_t gridbit,const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#else - mavlink_terrain_data_t packet; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - packet.gridbit = gridbit; - mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -} - -/** - * @brief Encode a terrain_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data) -{ - return mavlink_msg_terrain_data_pack(system_id, component_id, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); -} - -/** - * @brief Encode a terrain_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data) -{ - return mavlink_msg_terrain_data_pack_chan(system_id, component_id, chan, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); -} - -/** - * @brief Send a terrain_data message - * @param chan MAVLink channel to send the message - * - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param gridbit bit within the terrain request mask - * @param data Terrain data in meters AMSL - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_data_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#else - mavlink_terrain_data_t packet; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - packet.gridbit = gridbit; - mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#endif -} - -/** - * @brief Send a terrain_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_data_send_struct(mavlink_channel_t chan, const mavlink_terrain_data_t* terrain_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_data_send(chan, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)terrain_data, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#else - mavlink_terrain_data_t *packet = (mavlink_terrain_data_t *)msgbuf; - packet->lat = lat; - packet->lon = lon; - packet->grid_spacing = grid_spacing; - packet->gridbit = gridbit; - mav_array_memcpy(packet->data, data, sizeof(int16_t)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_DATA UNPACKING - - -/** - * @brief Get field lat from terrain_data message - * - * @return Latitude of SW corner of first grid (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_data_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lon from terrain_data message - * - * @return Longitude of SW corner of first grid (in degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_data_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field grid_spacing from terrain_data message - * - * @return Grid spacing in meters - */ -static inline uint16_t mavlink_msg_terrain_data_get_grid_spacing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field gridbit from terrain_data message - * - * @return bit within the terrain request mask - */ -static inline uint8_t mavlink_msg_terrain_data_get_gridbit(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field data from terrain_data message - * - * @return Terrain data in meters AMSL - */ -static inline uint16_t mavlink_msg_terrain_data_get_data(const mavlink_message_t* msg, int16_t *data) -{ - return _MAV_RETURN_int16_t_array(msg, data, 16, 10); -} - -/** - * @brief Decode a terrain_data message into a struct - * - * @param msg The message to decode - * @param terrain_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_data_decode(const mavlink_message_t* msg, mavlink_terrain_data_t* terrain_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_data->lat = mavlink_msg_terrain_data_get_lat(msg); - terrain_data->lon = mavlink_msg_terrain_data_get_lon(msg); - terrain_data->grid_spacing = mavlink_msg_terrain_data_get_grid_spacing(msg); - mavlink_msg_terrain_data_get_data(msg, terrain_data->data); - terrain_data->gridbit = mavlink_msg_terrain_data_get_gridbit(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_DATA_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_DATA_LEN; - memset(terrain_data, 0, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); - memcpy(terrain_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_terrain_report.h b/include/mavlink/v1.0/common/mavlink_msg_terrain_report.h deleted file mode 100644 index 1374db5..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_terrain_report.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_REPORT PACKING - -#define MAVLINK_MSG_ID_TERRAIN_REPORT 136 - -MAVPACKED( -typedef struct __mavlink_terrain_report_t { - int32_t lat; /*< Latitude (degrees *10^7)*/ - int32_t lon; /*< Longitude (degrees *10^7)*/ - float terrain_height; /*< Terrain height in meters AMSL*/ - float current_height; /*< Current vehicle height above lat/lon terrain height (meters)*/ - uint16_t spacing; /*< grid spacing (zero if terrain at this location unavailable)*/ - uint16_t pending; /*< Number of 4x4 terrain blocks waiting to be received or read from disk*/ - uint16_t loaded; /*< Number of 4x4 terrain blocks in memory*/ -}) mavlink_terrain_report_t; - -#define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22 -#define MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN 22 -#define MAVLINK_MSG_ID_136_LEN 22 -#define MAVLINK_MSG_ID_136_MIN_LEN 22 - -#define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC 1 -#define MAVLINK_MSG_ID_136_CRC 1 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT { \ - 136, \ - "TERRAIN_REPORT", \ - 7, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \ - { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \ - { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \ - { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ - { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \ - { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT { \ - "TERRAIN_REPORT", \ - 7, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \ - { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \ - { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \ - { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ - { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \ - { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_report 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 lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height Terrain height in meters AMSL - * @param current_height Current vehicle height above lat/lon terrain height (meters) - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#else - mavlink_terrain_report_t packet; - packet.lat = lat; - packet.lon = lon; - packet.terrain_height = terrain_height; - packet.current_height = current_height; - packet.spacing = spacing; - packet.pending = pending; - packet.loaded = loaded; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -} - -/** - * @brief Pack a terrain_report message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height Terrain height in meters AMSL - * @param current_height Current vehicle height above lat/lon terrain height (meters) - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon,uint16_t spacing,float terrain_height,float current_height,uint16_t pending,uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#else - mavlink_terrain_report_t packet; - packet.lat = lat; - packet.lon = lon; - packet.terrain_height = terrain_height; - packet.current_height = current_height; - packet.spacing = spacing; - packet.pending = pending; - packet.loaded = loaded; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -} - -/** - * @brief Encode a terrain_report struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_report C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report) -{ - return mavlink_msg_terrain_report_pack(system_id, component_id, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); -} - -/** - * @brief Encode a terrain_report struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_report C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report) -{ - return mavlink_msg_terrain_report_pack_chan(system_id, component_id, chan, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); -} - -/** - * @brief Send a terrain_report message - * @param chan MAVLink channel to send the message - * - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height Terrain height in meters AMSL - * @param current_height Current vehicle height above lat/lon terrain height (meters) - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_report_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#else - mavlink_terrain_report_t packet; - packet.lat = lat; - packet.lon = lon; - packet.terrain_height = terrain_height; - packet.current_height = current_height; - packet.spacing = spacing; - packet.pending = pending; - packet.loaded = loaded; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#endif -} - -/** - * @brief Send a terrain_report message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_report_send_struct(mavlink_channel_t chan, const mavlink_terrain_report_t* terrain_report) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_report_send(chan, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)terrain_report, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#else - mavlink_terrain_report_t *packet = (mavlink_terrain_report_t *)msgbuf; - packet->lat = lat; - packet->lon = lon; - packet->terrain_height = terrain_height; - packet->current_height = current_height; - packet->spacing = spacing; - packet->pending = pending; - packet->loaded = loaded; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_REPORT UNPACKING - - -/** - * @brief Get field lat from terrain_report message - * - * @return Latitude (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_report_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lon from terrain_report message - * - * @return Longitude (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_report_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field spacing from terrain_report message - * - * @return grid spacing (zero if terrain at this location unavailable) - */ -static inline uint16_t mavlink_msg_terrain_report_get_spacing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field terrain_height from terrain_report message - * - * @return Terrain height in meters AMSL - */ -static inline float mavlink_msg_terrain_report_get_terrain_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field current_height from terrain_report message - * - * @return Current vehicle height above lat/lon terrain height (meters) - */ -static inline float mavlink_msg_terrain_report_get_current_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field pending from terrain_report message - * - * @return Number of 4x4 terrain blocks waiting to be received or read from disk - */ -static inline uint16_t mavlink_msg_terrain_report_get_pending(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field loaded from terrain_report message - * - * @return Number of 4x4 terrain blocks in memory - */ -static inline uint16_t mavlink_msg_terrain_report_get_loaded(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Decode a terrain_report message into a struct - * - * @param msg The message to decode - * @param terrain_report C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_report_decode(const mavlink_message_t* msg, mavlink_terrain_report_t* terrain_report) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_report->lat = mavlink_msg_terrain_report_get_lat(msg); - terrain_report->lon = mavlink_msg_terrain_report_get_lon(msg); - terrain_report->terrain_height = mavlink_msg_terrain_report_get_terrain_height(msg); - terrain_report->current_height = mavlink_msg_terrain_report_get_current_height(msg); - terrain_report->spacing = mavlink_msg_terrain_report_get_spacing(msg); - terrain_report->pending = mavlink_msg_terrain_report_get_pending(msg); - terrain_report->loaded = mavlink_msg_terrain_report_get_loaded(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_REPORT_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_REPORT_LEN; - memset(terrain_report, 0, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); - memcpy(terrain_report, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_terrain_request.h b/include/mavlink/v1.0/common/mavlink_msg_terrain_request.h deleted file mode 100644 index 8924ed4..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_terrain_request.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_REQUEST PACKING - -#define MAVLINK_MSG_ID_TERRAIN_REQUEST 133 - -MAVPACKED( -typedef struct __mavlink_terrain_request_t { - uint64_t mask; /*< Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)*/ - int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/ - int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/ - uint16_t grid_spacing; /*< Grid spacing in meters*/ -}) mavlink_terrain_request_t; - -#define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18 -#define MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN 18 -#define MAVLINK_MSG_ID_133_LEN 18 -#define MAVLINK_MSG_ID_133_MIN_LEN 18 - -#define MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC 6 -#define MAVLINK_MSG_ID_133_CRC 6 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \ - 133, \ - "TERRAIN_REQUEST", \ - 4, \ - { { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \ - "TERRAIN_REQUEST", \ - 4, \ - { { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_request 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 lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#else - mavlink_terrain_request_t packet; - packet.mask = mask; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -} - -/** - * @brief Pack a terrain_request message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon,uint16_t grid_spacing,uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#else - mavlink_terrain_request_t packet; - packet.mask = mask; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -} - -/** - * @brief Encode a terrain_request struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request) -{ - return mavlink_msg_terrain_request_pack(system_id, component_id, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); -} - -/** - * @brief Encode a terrain_request struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request) -{ - return mavlink_msg_terrain_request_pack_chan(system_id, component_id, chan, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); -} - -/** - * @brief Send a terrain_request message - * @param chan MAVLink channel to send the message - * - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_request_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#else - mavlink_terrain_request_t packet; - packet.mask = mask; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#endif -} - -/** - * @brief Send a terrain_request message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_request_send_struct(mavlink_channel_t chan, const mavlink_terrain_request_t* terrain_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_request_send(chan, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)terrain_request, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#else - mavlink_terrain_request_t *packet = (mavlink_terrain_request_t *)msgbuf; - packet->mask = mask; - packet->lat = lat; - packet->lon = lon; - packet->grid_spacing = grid_spacing; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_REQUEST UNPACKING - - -/** - * @brief Get field lat from terrain_request message - * - * @return Latitude of SW corner of first grid (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_request_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from terrain_request message - * - * @return Longitude of SW corner of first grid (in degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_request_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field grid_spacing from terrain_request message - * - * @return Grid spacing in meters - */ -static inline uint16_t mavlink_msg_terrain_request_get_grid_spacing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field mask from terrain_request message - * - * @return Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - */ -static inline uint64_t mavlink_msg_terrain_request_get_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Decode a terrain_request message into a struct - * - * @param msg The message to decode - * @param terrain_request C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_request_decode(const mavlink_message_t* msg, mavlink_terrain_request_t* terrain_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_request->mask = mavlink_msg_terrain_request_get_mask(msg); - terrain_request->lat = mavlink_msg_terrain_request_get_lat(msg); - terrain_request->lon = mavlink_msg_terrain_request_get_lon(msg); - terrain_request->grid_spacing = mavlink_msg_terrain_request_get_grid_spacing(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN; - memset(terrain_request, 0, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); - memcpy(terrain_request, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_timesync.h b/include/mavlink/v1.0/common/mavlink_msg_timesync.h deleted file mode 100644 index 395211f..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_timesync.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE TIMESYNC PACKING - -#define MAVLINK_MSG_ID_TIMESYNC 111 - -MAVPACKED( -typedef struct __mavlink_timesync_t { - int64_t tc1; /*< Time sync timestamp 1*/ - int64_t ts1; /*< Time sync timestamp 2*/ -}) mavlink_timesync_t; - -#define MAVLINK_MSG_ID_TIMESYNC_LEN 16 -#define MAVLINK_MSG_ID_TIMESYNC_MIN_LEN 16 -#define MAVLINK_MSG_ID_111_LEN 16 -#define MAVLINK_MSG_ID_111_MIN_LEN 16 - -#define MAVLINK_MSG_ID_TIMESYNC_CRC 34 -#define MAVLINK_MSG_ID_111_CRC 34 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TIMESYNC { \ - 111, \ - "TIMESYNC", \ - 2, \ - { { "tc1", NULL, MAVLINK_TYPE_INT64_T, 0, 0, offsetof(mavlink_timesync_t, tc1) }, \ - { "ts1", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_timesync_t, ts1) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TIMESYNC { \ - "TIMESYNC", \ - 2, \ - { { "tc1", NULL, MAVLINK_TYPE_INT64_T, 0, 0, offsetof(mavlink_timesync_t, tc1) }, \ - { "ts1", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_timesync_t, ts1) }, \ - } \ -} -#endif - -/** - * @brief Pack a timesync 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 tc1 Time sync timestamp 1 - * @param ts1 Time sync timestamp 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_timesync_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int64_t tc1, int64_t ts1) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN); -#else - mavlink_timesync_t packet; - packet.tc1 = tc1; - packet.ts1 = ts1; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TIMESYNC; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -} - -/** - * @brief Pack a timesync message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param tc1 Time sync timestamp 1 - * @param ts1 Time sync timestamp 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_timesync_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int64_t tc1,int64_t ts1) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN); -#else - mavlink_timesync_t packet; - packet.tc1 = tc1; - packet.ts1 = ts1; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TIMESYNC; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -} - -/** - * @brief Encode a timesync struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param timesync C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_timesync_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_timesync_t* timesync) -{ - return mavlink_msg_timesync_pack(system_id, component_id, msg, timesync->tc1, timesync->ts1); -} - -/** - * @brief Encode a timesync struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param timesync C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_timesync_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_timesync_t* timesync) -{ - return mavlink_msg_timesync_pack_chan(system_id, component_id, chan, msg, timesync->tc1, timesync->ts1); -} - -/** - * @brief Send a timesync message - * @param chan MAVLink channel to send the message - * - * @param tc1 Time sync timestamp 1 - * @param ts1 Time sync timestamp 2 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_timesync_send(mavlink_channel_t chan, int64_t tc1, int64_t ts1) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#else - mavlink_timesync_t packet; - packet.tc1 = tc1; - packet.ts1 = ts1; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)&packet, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#endif -} - -/** - * @brief Send a timesync message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_timesync_send_struct(mavlink_channel_t chan, const mavlink_timesync_t* timesync) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_timesync_send(chan, timesync->tc1, timesync->ts1); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)timesync, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TIMESYNC_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_timesync_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int64_t tc1, int64_t ts1) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#else - mavlink_timesync_t *packet = (mavlink_timesync_t *)msgbuf; - packet->tc1 = tc1; - packet->ts1 = ts1; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)packet, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TIMESYNC UNPACKING - - -/** - * @brief Get field tc1 from timesync message - * - * @return Time sync timestamp 1 - */ -static inline int64_t mavlink_msg_timesync_get_tc1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int64_t(msg, 0); -} - -/** - * @brief Get field ts1 from timesync message - * - * @return Time sync timestamp 2 - */ -static inline int64_t mavlink_msg_timesync_get_ts1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int64_t(msg, 8); -} - -/** - * @brief Decode a timesync message into a struct - * - * @param msg The message to decode - * @param timesync C-struct to decode the message contents into - */ -static inline void mavlink_msg_timesync_decode(const mavlink_message_t* msg, mavlink_timesync_t* timesync) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - timesync->tc1 = mavlink_msg_timesync_get_tc1(msg); - timesync->ts1 = mavlink_msg_timesync_get_ts1(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TIMESYNC_LEN? msg->len : MAVLINK_MSG_ID_TIMESYNC_LEN; - memset(timesync, 0, MAVLINK_MSG_ID_TIMESYNC_LEN); - memcpy(timesync, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_v2_extension.h b/include/mavlink/v1.0/common/mavlink_msg_v2_extension.h deleted file mode 100644 index 31777f2..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_v2_extension.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE V2_EXTENSION PACKING - -#define MAVLINK_MSG_ID_V2_EXTENSION 248 - -MAVPACKED( -typedef struct __mavlink_v2_extension_t { - uint16_t message_type; /*< A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.*/ - uint8_t target_network; /*< Network ID (0 for broadcast)*/ - uint8_t target_system; /*< System ID (0 for broadcast)*/ - uint8_t target_component; /*< Component ID (0 for broadcast)*/ - uint8_t payload[249]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/ -}) mavlink_v2_extension_t; - -#define MAVLINK_MSG_ID_V2_EXTENSION_LEN 254 -#define MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN 254 -#define MAVLINK_MSG_ID_248_LEN 254 -#define MAVLINK_MSG_ID_248_MIN_LEN 254 - -#define MAVLINK_MSG_ID_V2_EXTENSION_CRC 8 -#define MAVLINK_MSG_ID_248_CRC 8 - -#define MAVLINK_MSG_V2_EXTENSION_FIELD_PAYLOAD_LEN 249 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \ - 248, \ - "V2_EXTENSION", \ - 5, \ - { { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ - { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \ - "V2_EXTENSION", \ - 5, \ - { { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ - { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \ - } \ -} -#endif - -/** - * @brief Pack a v2_extension message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_v2_extension_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#else - mavlink_v2_extension_t packet; - packet.message_type = message_type; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -} - -/** - * @brief Pack a v2_extension message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_v2_extension_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_network,uint8_t target_system,uint8_t target_component,uint16_t message_type,const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#else - mavlink_v2_extension_t packet; - packet.message_type = message_type; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -} - -/** - * @brief Encode a v2_extension struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param v2_extension C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_v2_extension_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension) -{ - return mavlink_msg_v2_extension_pack(system_id, component_id, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); -} - -/** - * @brief Encode a v2_extension struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param v2_extension C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_v2_extension_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension) -{ - return mavlink_msg_v2_extension_pack_chan(system_id, component_id, chan, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); -} - -/** - * @brief Send a v2_extension message - * @param chan MAVLink channel to send the message - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_v2_extension_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#else - mavlink_v2_extension_t packet; - packet.message_type = message_type; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#endif -} - -/** - * @brief Send a v2_extension message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_v2_extension_send_struct(mavlink_channel_t chan, const mavlink_v2_extension_t* v2_extension) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_v2_extension_send(chan, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)v2_extension, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_V2_EXTENSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_v2_extension_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#else - mavlink_v2_extension_t *packet = (mavlink_v2_extension_t *)msgbuf; - packet->message_type = message_type; - packet->target_network = target_network; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE V2_EXTENSION UNPACKING - - -/** - * @brief Get field target_network from v2_extension message - * - * @return Network ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_v2_extension_get_target_network(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_system from v2_extension message - * - * @return System ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_v2_extension_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field target_component from v2_extension message - * - * @return Component ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_v2_extension_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field message_type from v2_extension message - * - * @return A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - */ -static inline uint16_t mavlink_msg_v2_extension_get_message_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field payload from v2_extension message - * - * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - */ -static inline uint16_t mavlink_msg_v2_extension_get_payload(const mavlink_message_t* msg, uint8_t *payload) -{ - return _MAV_RETURN_uint8_t_array(msg, payload, 249, 5); -} - -/** - * @brief Decode a v2_extension message into a struct - * - * @param msg The message to decode - * @param v2_extension C-struct to decode the message contents into - */ -static inline void mavlink_msg_v2_extension_decode(const mavlink_message_t* msg, mavlink_v2_extension_t* v2_extension) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - v2_extension->message_type = mavlink_msg_v2_extension_get_message_type(msg); - v2_extension->target_network = mavlink_msg_v2_extension_get_target_network(msg); - v2_extension->target_system = mavlink_msg_v2_extension_get_target_system(msg); - v2_extension->target_component = mavlink_msg_v2_extension_get_target_component(msg); - mavlink_msg_v2_extension_get_payload(msg, v2_extension->payload); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_V2_EXTENSION_LEN? msg->len : MAVLINK_MSG_ID_V2_EXTENSION_LEN; - memset(v2_extension, 0, MAVLINK_MSG_ID_V2_EXTENSION_LEN); - memcpy(v2_extension, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h b/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h deleted file mode 100644 index 1700dd0..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h +++ /dev/null @@ -1,338 +0,0 @@ -#pragma once -// MESSAGE VFR_HUD PACKING - -#define MAVLINK_MSG_ID_VFR_HUD 74 - -MAVPACKED( -typedef struct __mavlink_vfr_hud_t { - float airspeed; /*< Current airspeed in m/s*/ - float groundspeed; /*< Current ground speed in m/s*/ - float alt; /*< Current altitude (MSL), in meters*/ - float climb; /*< Current climb rate in meters/second*/ - int16_t heading; /*< Current heading in degrees, in compass units (0..360, 0=north)*/ - uint16_t throttle; /*< Current throttle setting in integer percent, 0 to 100*/ -}) mavlink_vfr_hud_t; - -#define MAVLINK_MSG_ID_VFR_HUD_LEN 20 -#define MAVLINK_MSG_ID_VFR_HUD_MIN_LEN 20 -#define MAVLINK_MSG_ID_74_LEN 20 -#define MAVLINK_MSG_ID_74_MIN_LEN 20 - -#define MAVLINK_MSG_ID_VFR_HUD_CRC 20 -#define MAVLINK_MSG_ID_74_CRC 20 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VFR_HUD { \ - 74, \ - "VFR_HUD", \ - 6, \ - { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ - { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ - { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ - { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VFR_HUD { \ - "VFR_HUD", \ - 6, \ - { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ - { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ - { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ - { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ - } \ -} -#endif - -/** - * @brief Pack a vfr_hud 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 airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - - 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, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -} - -/** - * @brief Pack a vfr_hud message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - - 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, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -} - -/** - * @brief Encode a vfr_hud struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vfr_hud C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) -{ - return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); -} - -/** - * @brief Encode a vfr_hud struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vfr_hud C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vfr_hud_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) -{ - return mavlink_msg_vfr_hud_pack_chan(system_id, component_id, chan, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); -} - -/** - * @brief Send a vfr_hud message - * @param chan MAVLink channel to send the message - * - * @param airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[MAVLINK_MSG_ID_VFR_HUD_LEN]; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _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, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#endif -} - -/** - * @brief Send a vfr_hud message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vfr_hud_send_struct(mavlink_channel_t chan, const mavlink_vfr_hud_t* vfr_hud) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vfr_hud_send(chan, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)vfr_hud, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VFR_HUD_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vfr_hud_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _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, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - mavlink_vfr_hud_t *packet = (mavlink_vfr_hud_t *)msgbuf; - packet->airspeed = airspeed; - packet->groundspeed = groundspeed; - packet->alt = alt; - packet->climb = climb; - packet->heading = heading; - packet->throttle = throttle; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VFR_HUD UNPACKING - - -/** - * @brief Get field airspeed from vfr_hud message - * - * @return Current airspeed in m/s - */ -static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field groundspeed from vfr_hud message - * - * @return Current ground speed in m/s - */ -static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field heading from vfr_hud message - * - * @return Current heading in degrees, in compass units (0..360, 0=north) - */ -static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field throttle from vfr_hud message - * - * @return Current throttle setting in integer percent, 0 to 100 - */ -static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field alt from vfr_hud message - * - * @return Current altitude (MSL), in meters - */ -static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field climb from vfr_hud message - * - * @return Current climb rate in meters/second - */ -static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a vfr_hud message into a struct - * - * @param msg The message to decode - * @param vfr_hud C-struct to decode the message contents into - */ -static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg); - vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg); - vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg); - vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg); - vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg); - vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VFR_HUD_LEN? msg->len : MAVLINK_MSG_ID_VFR_HUD_LEN; - memset(vfr_hud, 0, MAVLINK_MSG_ID_VFR_HUD_LEN); - memcpy(vfr_hud, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_vibration.h b/include/mavlink/v1.0/common/mavlink_msg_vibration.h deleted file mode 100644 index a8760f7..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_vibration.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE VIBRATION PACKING - -#define MAVLINK_MSG_ID_VIBRATION 241 - -MAVPACKED( -typedef struct __mavlink_vibration_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float vibration_x; /*< Vibration levels on X-axis*/ - float vibration_y; /*< Vibration levels on Y-axis*/ - float vibration_z; /*< Vibration levels on Z-axis*/ - uint32_t clipping_0; /*< first accelerometer clipping count*/ - uint32_t clipping_1; /*< second accelerometer clipping count*/ - uint32_t clipping_2; /*< third accelerometer clipping count*/ -}) mavlink_vibration_t; - -#define MAVLINK_MSG_ID_VIBRATION_LEN 32 -#define MAVLINK_MSG_ID_VIBRATION_MIN_LEN 32 -#define MAVLINK_MSG_ID_241_LEN 32 -#define MAVLINK_MSG_ID_241_MIN_LEN 32 - -#define MAVLINK_MSG_ID_VIBRATION_CRC 90 -#define MAVLINK_MSG_ID_241_CRC 90 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VIBRATION { \ - 241, \ - "VIBRATION", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \ - { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \ - { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \ - { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \ - { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \ - { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \ - { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VIBRATION { \ - "VIBRATION", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \ - { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \ - { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \ - { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \ - { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \ - { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \ - { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \ - } \ -} -#endif - -/** - * @brief Pack a vibration 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 (micros since boot or Unix epoch) - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN); -#else - mavlink_vibration_t packet; - packet.time_usec = time_usec; - packet.vibration_x = vibration_x; - packet.vibration_y = vibration_y; - packet.vibration_z = vibration_z; - packet.clipping_0 = clipping_0; - packet.clipping_1 = clipping_1; - packet.clipping_2 = clipping_2; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIBRATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -} - -/** - * @brief Pack a vibration message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float vibration_x,float vibration_y,float vibration_z,uint32_t clipping_0,uint32_t clipping_1,uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN); -#else - mavlink_vibration_t packet; - packet.time_usec = time_usec; - packet.vibration_x = vibration_x; - packet.vibration_y = vibration_y; - packet.vibration_z = vibration_z; - packet.clipping_0 = clipping_0; - packet.clipping_1 = clipping_1; - packet.clipping_2 = clipping_2; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIBRATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -} - -/** - * @brief Encode a vibration struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vibration C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vibration_t* vibration) -{ - return mavlink_msg_vibration_pack(system_id, component_id, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); -} - -/** - * @brief Encode a vibration struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vibration C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vibration_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vibration_t* vibration) -{ - return mavlink_msg_vibration_pack_chan(system_id, component_id, chan, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); -} - -/** - * @brief Send a vibration message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vibration_send(mavlink_channel_t chan, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#else - mavlink_vibration_t packet; - packet.time_usec = time_usec; - packet.vibration_x = vibration_x; - packet.vibration_y = vibration_y; - packet.vibration_z = vibration_z; - packet.clipping_0 = clipping_0; - packet.clipping_1 = clipping_1; - packet.clipping_2 = clipping_2; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)&packet, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#endif -} - -/** - * @brief Send a vibration message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vibration_send_struct(mavlink_channel_t chan, const mavlink_vibration_t* vibration) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vibration_send(chan, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)vibration, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VIBRATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vibration_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#else - mavlink_vibration_t *packet = (mavlink_vibration_t *)msgbuf; - packet->time_usec = time_usec; - packet->vibration_x = vibration_x; - packet->vibration_y = vibration_y; - packet->vibration_z = vibration_z; - packet->clipping_0 = clipping_0; - packet->clipping_1 = clipping_1; - packet->clipping_2 = clipping_2; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)packet, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VIBRATION UNPACKING - - -/** - * @brief Get field time_usec from vibration message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_vibration_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field vibration_x from vibration message - * - * @return Vibration levels on X-axis - */ -static inline float mavlink_msg_vibration_get_vibration_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field vibration_y from vibration message - * - * @return Vibration levels on Y-axis - */ -static inline float mavlink_msg_vibration_get_vibration_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vibration_z from vibration message - * - * @return Vibration levels on Z-axis - */ -static inline float mavlink_msg_vibration_get_vibration_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field clipping_0 from vibration message - * - * @return first accelerometer clipping count - */ -static inline uint32_t mavlink_msg_vibration_get_clipping_0(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field clipping_1 from vibration message - * - * @return second accelerometer clipping count - */ -static inline uint32_t mavlink_msg_vibration_get_clipping_1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 24); -} - -/** - * @brief Get field clipping_2 from vibration message - * - * @return third accelerometer clipping count - */ -static inline uint32_t mavlink_msg_vibration_get_clipping_2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 28); -} - -/** - * @brief Decode a vibration message into a struct - * - * @param msg The message to decode - * @param vibration C-struct to decode the message contents into - */ -static inline void mavlink_msg_vibration_decode(const mavlink_message_t* msg, mavlink_vibration_t* vibration) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vibration->time_usec = mavlink_msg_vibration_get_time_usec(msg); - vibration->vibration_x = mavlink_msg_vibration_get_vibration_x(msg); - vibration->vibration_y = mavlink_msg_vibration_get_vibration_y(msg); - vibration->vibration_z = mavlink_msg_vibration_get_vibration_z(msg); - vibration->clipping_0 = mavlink_msg_vibration_get_clipping_0(msg); - vibration->clipping_1 = mavlink_msg_vibration_get_clipping_1(msg); - vibration->clipping_2 = mavlink_msg_vibration_get_clipping_2(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VIBRATION_LEN? msg->len : MAVLINK_MSG_ID_VIBRATION_LEN; - memset(vibration, 0, MAVLINK_MSG_ID_VIBRATION_LEN); - memcpy(vibration, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h b/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h deleted file mode 100644 index 5813b74..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE VICON_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104 - -MAVPACKED( -typedef struct __mavlink_vicon_position_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X position*/ - float y; /*< Global Y position*/ - float z; /*< Global Z position*/ - float roll; /*< Roll angle in rad*/ - float pitch; /*< Pitch angle in rad*/ - float yaw; /*< Yaw angle in rad*/ -}) mavlink_vicon_position_estimate_t; - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN 32 -#define MAVLINK_MSG_ID_104_LEN 32 -#define MAVLINK_MSG_ID_104_MIN_LEN 32 - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC 56 -#define MAVLINK_MSG_ID_104_CRC 56 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ - 104, \ - "VICON_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ - "VICON_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a vicon_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Pack a vicon_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Encode a vicon_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vicon_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ - return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); -} - -/** - * @brief Encode a vicon_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vicon_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ - return mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, chan, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); -} - -/** - * @brief Send a vicon_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a vicon_position_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vicon_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vicon_position_estimate_send(chan, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)vicon_position_estimate, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vicon_position_estimate_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - mavlink_vicon_position_estimate_t *packet = (mavlink_vicon_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VICON_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vicon_position_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vicon_position_estimate message - * - * @return Global X position - */ -static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vicon_position_estimate message - * - * @return Global Y position - */ -static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vicon_position_estimate message - * - * @return Global Z position - */ -static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from vicon_position_estimate message - * - * @return Roll angle in rad - */ -static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from vicon_position_estimate message - * - * @return Pitch angle in rad - */ -static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from vicon_position_estimate message - * - * @return Yaw angle in rad - */ -static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a vicon_position_estimate message into a struct - * - * @param msg The message to decode - * @param vicon_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg); - vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg); - vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg); - vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg); - vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN; - memset(vicon_position_estimate, 0, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); - memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h b/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h deleted file mode 100644 index 0c351e0..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE VISION_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102 - -MAVPACKED( -typedef struct __mavlink_vision_position_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X position*/ - float y; /*< Global Y position*/ - float z; /*< Global Z position*/ - float roll; /*< Roll angle in rad*/ - float pitch; /*< Pitch angle in rad*/ - float yaw; /*< Yaw angle in rad*/ -}) mavlink_vision_position_estimate_t; - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN 32 -#define MAVLINK_MSG_ID_102_LEN 32 -#define MAVLINK_MSG_ID_102_MIN_LEN 32 - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC 158 -#define MAVLINK_MSG_ID_102_CRC 158 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ - 102, \ - "VISION_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ - "VISION_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a vision_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Pack a vision_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Encode a vision_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) -{ - return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); -} - -/** - * @brief Encode a vision_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) -{ - return mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); -} - -/** - * @brief Send a vision_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a vision_position_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vision_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_vision_position_estimate_t* vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vision_position_estimate_send(chan, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)vision_position_estimate, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_vision_position_estimate_t *packet = (mavlink_vision_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VISION_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vision_position_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vision_position_estimate message - * - * @return Global X position - */ -static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vision_position_estimate message - * - * @return Global Y position - */ -static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vision_position_estimate message - * - * @return Global Z position - */ -static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from vision_position_estimate message - * - * @return Roll angle in rad - */ -static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from vision_position_estimate message - * - * @return Pitch angle in rad - */ -static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from vision_position_estimate message - * - * @return Yaw angle in rad - */ -static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a vision_position_estimate message into a struct - * - * @param msg The message to decode - * @param vision_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg); - vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg); - vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg); - vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg); - vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN; - memset(vision_position_estimate, 0, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); - memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h b/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h deleted file mode 100644 index bca0947..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE VISION_SPEED_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 - -MAVPACKED( -typedef struct __mavlink_vision_speed_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X speed*/ - float y; /*< Global Y speed*/ - float z; /*< Global Z speed*/ -}) mavlink_vision_speed_estimate_t; - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN 20 -#define MAVLINK_MSG_ID_103_LEN 20 -#define MAVLINK_MSG_ID_103_MIN_LEN 20 - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208 -#define MAVLINK_MSG_ID_103_CRC 208 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ - 103, \ - "VISION_SPEED_ESTIMATE", \ - 4, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ - "VISION_SPEED_ESTIMATE", \ - 4, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ - } \ -} -#endif - -/** - * @brief Pack a vision_speed_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - - 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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -} - -/** - * @brief Pack a vision_speed_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t usec,float x,float y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - - 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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -} - -/** - * @brief Encode a vision_speed_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vision_speed_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ - return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); -} - -/** - * @brief Encode a vision_speed_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vision_speed_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ - return mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, chan, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); -} - -/** - * @brief Send a vision_speed_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a vision_speed_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vision_speed_estimate_send_struct(mavlink_channel_t chan, const mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vision_speed_estimate_send(chan, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)vision_speed_estimate, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - mavlink_vision_speed_estimate_t *packet = (mavlink_vision_speed_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VISION_SPEED_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vision_speed_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vision_speed_estimate message - * - * @return Global X speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vision_speed_estimate message - * - * @return Global Y speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vision_speed_estimate message - * - * @return Global Z speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a vision_speed_estimate message into a struct - * - * @param msg The message to decode - * @param vision_speed_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg); - vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg); - vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg); - vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN; - memset(vision_speed_estimate, 0, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); - memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/mavlink_msg_wind_cov.h b/include/mavlink/v1.0/common/mavlink_msg_wind_cov.h deleted file mode 100644 index 0562fb0..0000000 --- a/include/mavlink/v1.0/common/mavlink_msg_wind_cov.h +++ /dev/null @@ -1,413 +0,0 @@ -#pragma once -// MESSAGE WIND_COV PACKING - -#define MAVLINK_MSG_ID_WIND_COV 231 - -MAVPACKED( -typedef struct __mavlink_wind_cov_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float wind_x; /*< Wind in X (NED) direction in m/s*/ - float wind_y; /*< Wind in Y (NED) direction in m/s*/ - float wind_z; /*< Wind in Z (NED) direction in m/s*/ - float var_horiz; /*< Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate.*/ - float var_vert; /*< Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate.*/ - float wind_alt; /*< AMSL altitude (m) this measurement was taken at*/ - float horiz_accuracy; /*< Horizontal speed 1-STD accuracy*/ - float vert_accuracy; /*< Vertical speed 1-STD accuracy*/ -}) mavlink_wind_cov_t; - -#define MAVLINK_MSG_ID_WIND_COV_LEN 40 -#define MAVLINK_MSG_ID_WIND_COV_MIN_LEN 40 -#define MAVLINK_MSG_ID_231_LEN 40 -#define MAVLINK_MSG_ID_231_MIN_LEN 40 - -#define MAVLINK_MSG_ID_WIND_COV_CRC 105 -#define MAVLINK_MSG_ID_231_CRC 105 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_WIND_COV { \ - 231, \ - "WIND_COV", \ - 9, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wind_cov_t, time_usec) }, \ - { "wind_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_cov_t, wind_x) }, \ - { "wind_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_wind_cov_t, wind_y) }, \ - { "wind_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_wind_cov_t, wind_z) }, \ - { "var_horiz", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_wind_cov_t, var_horiz) }, \ - { "var_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_wind_cov_t, var_vert) }, \ - { "wind_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_wind_cov_t, wind_alt) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_wind_cov_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_wind_cov_t, vert_accuracy) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_WIND_COV { \ - "WIND_COV", \ - 9, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wind_cov_t, time_usec) }, \ - { "wind_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_cov_t, wind_x) }, \ - { "wind_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_wind_cov_t, wind_y) }, \ - { "wind_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_wind_cov_t, wind_z) }, \ - { "var_horiz", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_wind_cov_t, var_horiz) }, \ - { "var_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_wind_cov_t, var_vert) }, \ - { "wind_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_wind_cov_t, wind_alt) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_wind_cov_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_wind_cov_t, vert_accuracy) }, \ - } \ -} -#endif - -/** - * @brief Pack a wind_cov 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 (micros since boot or Unix epoch) - * @param wind_x Wind in X (NED) direction in m/s - * @param wind_y Wind in Y (NED) direction in m/s - * @param wind_z Wind in Z (NED) direction in m/s - * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - * @param wind_alt AMSL altitude (m) this measurement was taken at - * @param horiz_accuracy Horizontal speed 1-STD accuracy - * @param vert_accuracy Vertical speed 1-STD accuracy - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wind_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_COV_LEN); -#else - mavlink_wind_cov_t packet; - packet.time_usec = time_usec; - packet.wind_x = wind_x; - packet.wind_y = wind_y; - packet.wind_z = wind_z; - packet.var_horiz = var_horiz; - packet.var_vert = var_vert; - packet.wind_alt = wind_alt; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WIND_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -} - -/** - * @brief Pack a wind_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param wind_x Wind in X (NED) direction in m/s - * @param wind_y Wind in Y (NED) direction in m/s - * @param wind_z Wind in Z (NED) direction in m/s - * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - * @param wind_alt AMSL altitude (m) this measurement was taken at - * @param horiz_accuracy Horizontal speed 1-STD accuracy - * @param vert_accuracy Vertical speed 1-STD accuracy - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wind_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float wind_x,float wind_y,float wind_z,float var_horiz,float var_vert,float wind_alt,float horiz_accuracy,float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_COV_LEN); -#else - mavlink_wind_cov_t packet; - packet.time_usec = time_usec; - packet.wind_x = wind_x; - packet.wind_y = wind_y; - packet.wind_z = wind_z; - packet.var_horiz = var_horiz; - packet.var_vert = var_vert; - packet.wind_alt = wind_alt; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WIND_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -} - -/** - * @brief Encode a wind_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param wind_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wind_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wind_cov_t* wind_cov) -{ - return mavlink_msg_wind_cov_pack(system_id, component_id, msg, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); -} - -/** - * @brief Encode a wind_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param wind_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wind_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wind_cov_t* wind_cov) -{ - return mavlink_msg_wind_cov_pack_chan(system_id, component_id, chan, msg, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); -} - -/** - * @brief Send a wind_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param wind_x Wind in X (NED) direction in m/s - * @param wind_y Wind in Y (NED) direction in m/s - * @param wind_z Wind in Z (NED) direction in m/s - * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - * @param wind_alt AMSL altitude (m) this measurement was taken at - * @param horiz_accuracy Horizontal speed 1-STD accuracy - * @param vert_accuracy Vertical speed 1-STD accuracy - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_wind_cov_send(mavlink_channel_t chan, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#else - mavlink_wind_cov_t packet; - packet.time_usec = time_usec; - packet.wind_x = wind_x; - packet.wind_y = wind_y; - packet.wind_z = wind_z; - packet.var_horiz = var_horiz; - packet.var_vert = var_vert; - packet.wind_alt = wind_alt; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)&packet, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#endif -} - -/** - * @brief Send a wind_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_wind_cov_send_struct(mavlink_channel_t chan, const mavlink_wind_cov_t* wind_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_wind_cov_send(chan, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)wind_cov, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_WIND_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_wind_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#else - mavlink_wind_cov_t *packet = (mavlink_wind_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->wind_x = wind_x; - packet->wind_y = wind_y; - packet->wind_z = wind_z; - packet->var_horiz = var_horiz; - packet->var_vert = var_vert; - packet->wind_alt = wind_alt; - packet->horiz_accuracy = horiz_accuracy; - packet->vert_accuracy = vert_accuracy; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)packet, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE WIND_COV UNPACKING - - -/** - * @brief Get field time_usec from wind_cov message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_wind_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field wind_x from wind_cov message - * - * @return Wind in X (NED) direction in m/s - */ -static inline float mavlink_msg_wind_cov_get_wind_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field wind_y from wind_cov message - * - * @return Wind in Y (NED) direction in m/s - */ -static inline float mavlink_msg_wind_cov_get_wind_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field wind_z from wind_cov message - * - * @return Wind in Z (NED) direction in m/s - */ -static inline float mavlink_msg_wind_cov_get_wind_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field var_horiz from wind_cov message - * - * @return Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - */ -static inline float mavlink_msg_wind_cov_get_var_horiz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field var_vert from wind_cov message - * - * @return Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - */ -static inline float mavlink_msg_wind_cov_get_var_vert(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field wind_alt from wind_cov message - * - * @return AMSL altitude (m) this measurement was taken at - */ -static inline float mavlink_msg_wind_cov_get_wind_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field horiz_accuracy from wind_cov message - * - * @return Horizontal speed 1-STD accuracy - */ -static inline float mavlink_msg_wind_cov_get_horiz_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field vert_accuracy from wind_cov message - * - * @return Vertical speed 1-STD accuracy - */ -static inline float mavlink_msg_wind_cov_get_vert_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a wind_cov message into a struct - * - * @param msg The message to decode - * @param wind_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_wind_cov_decode(const mavlink_message_t* msg, mavlink_wind_cov_t* wind_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - wind_cov->time_usec = mavlink_msg_wind_cov_get_time_usec(msg); - wind_cov->wind_x = mavlink_msg_wind_cov_get_wind_x(msg); - wind_cov->wind_y = mavlink_msg_wind_cov_get_wind_y(msg); - wind_cov->wind_z = mavlink_msg_wind_cov_get_wind_z(msg); - wind_cov->var_horiz = mavlink_msg_wind_cov_get_var_horiz(msg); - wind_cov->var_vert = mavlink_msg_wind_cov_get_var_vert(msg); - wind_cov->wind_alt = mavlink_msg_wind_cov_get_wind_alt(msg); - wind_cov->horiz_accuracy = mavlink_msg_wind_cov_get_horiz_accuracy(msg); - wind_cov->vert_accuracy = mavlink_msg_wind_cov_get_vert_accuracy(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_WIND_COV_LEN? msg->len : MAVLINK_MSG_ID_WIND_COV_LEN; - memset(wind_cov, 0, MAVLINK_MSG_ID_WIND_COV_LEN); - memcpy(wind_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v1.0/common/testsuite.h b/include/mavlink/v1.0/common/testsuite.h deleted file mode 100644 index 1952d02..0000000 --- a/include/mavlink/v1.0/common/testsuite.h +++ /dev/null @@ -1,8386 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from common.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#pragma once -#ifndef COMMON_TESTSUITE_H -#define COMMON_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL - -static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - - mavlink_test_common(system_id, component_id, last_msg); -} -#endif - - - - -static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0); - if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HEARTBEAT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_heartbeat_t packet_in = { - 963497464,17,84,151,218,3 - }; - mavlink_heartbeat_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.custom_mode = packet_in.custom_mode; - packet1.type = packet_in.type; - packet1.autopilot = packet_in.autopilot; - packet1.base_mode = packet_in.base_mode; - packet1.system_status = packet_in.system_status; - packet1.mavlink_version = packet_in.mavlink_version; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SYS_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_sys_status_t packet_in = { - 963497464,963497672,963497880,17859,17963,18067,18171,18275,18379,18483,18587,18691,223 - }; - mavlink_sys_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.onboard_control_sensors_present = packet_in.onboard_control_sensors_present; - packet1.onboard_control_sensors_enabled = packet_in.onboard_control_sensors_enabled; - packet1.onboard_control_sensors_health = packet_in.onboard_control_sensors_health; - packet1.load = packet_in.load; - packet1.voltage_battery = packet_in.voltage_battery; - packet1.current_battery = packet_in.current_battery; - packet1.drop_rate_comm = packet_in.drop_rate_comm; - packet1.errors_comm = packet_in.errors_comm; - packet1.errors_count1 = packet_in.errors_count1; - packet1.errors_count2 = packet_in.errors_count2; - packet1.errors_count3 = packet_in.errors_count3; - packet1.errors_count4 = packet_in.errors_count4; - packet1.battery_remaining = packet_in.battery_remaining; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sys_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_sys_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sys_status_pack(system_id, component_id, &msg , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 ); - mavlink_msg_sys_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sys_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 ); - mavlink_msg_sys_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SYSTEM_TIME >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_system_time_t packet_in = { - 93372036854775807ULL,963497880 - }; - mavlink_system_time_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_unix_usec = packet_in.time_unix_usec; - packet1.time_boot_ms = packet_in.time_boot_ms; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_system_time_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_system_time_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_system_time_pack(system_id, component_id, &msg , packet1.time_unix_usec , packet1.time_boot_ms ); - mavlink_msg_system_time_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_system_time_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_unix_usec , packet1.time_boot_ms ); - mavlink_msg_system_time_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PING >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_ping_t packet_in = { - 93372036854775807ULL,963497880,41,108 - }; - mavlink_ping_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PING_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PING_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ping_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_ping_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ping_pack(system_id, component_id, &msg , packet1.time_usec , packet1.seq , packet1.target_system , packet1.target_component ); - mavlink_msg_ping_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ping_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.seq , packet1.target_system , packet1.target_component ); - mavlink_msg_ping_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_change_operator_control_t packet_in = { - 5,72,139,"DEFGHIJKLMNOPQRSTUVWXYZA" - }; - mavlink_change_operator_control_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.control_request = packet_in.control_request; - packet1.version = packet_in.version; - - mav_array_memcpy(packet1.passkey, packet_in.passkey, sizeof(char)*25); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_change_operator_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey ); - mavlink_msg_change_operator_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey ); - mavlink_msg_change_operator_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_change_operator_control_ack_t packet_in = { - 5,72,139 - }; - mavlink_change_operator_control_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.gcs_system_id = packet_in.gcs_system_id; - packet1.control_request = packet_in.control_request; - packet1.ack = packet_in.ack; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_change_operator_control_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_ack_pack(system_id, component_id, &msg , packet1.gcs_system_id , packet1.control_request , packet1.ack ); - mavlink_msg_change_operator_control_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.gcs_system_id , packet1.control_request , packet1.ack ); - mavlink_msg_change_operator_control_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AUTH_KEY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_auth_key_t packet_in = { - "ABCDEFGHIJKLMNOPQRSTUVWXYZABCDE" - }; - mavlink_auth_key_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - - mav_array_memcpy(packet1.key, packet_in.key, sizeof(char)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_auth_key_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_auth_key_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_auth_key_pack(system_id, component_id, &msg , packet1.key ); - mavlink_msg_auth_key_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_auth_key_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.key ); - mavlink_msg_auth_key_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_MODE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_mode_t packet_in = { - 963497464,17,84 - }; - mavlink_set_mode_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.custom_mode = packet_in.custom_mode; - packet1.target_system = packet_in.target_system; - packet1.base_mode = packet_in.base_mode; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_MODE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_MODE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_mode_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_mode_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_mode_pack(system_id, component_id, &msg , packet1.target_system , packet1.base_mode , packet1.custom_mode ); - mavlink_msg_set_mode_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_mode_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.base_mode , packet1.custom_mode ); - mavlink_msg_set_mode_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_REQUEST_READ >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_request_read_t packet_in = { - 17235,139,206,"EFGHIJKLMNOPQRS" - }; - mavlink_param_request_read_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_index = packet_in.param_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_read_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_read_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index ); - mavlink_msg_param_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_read_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index ); - mavlink_msg_param_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_REQUEST_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_request_list_t packet_in = { - 5,72 - }; - mavlink_param_request_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_param_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_param_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_VALUE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_value_t packet_in = { - 17.0,17443,17547,"IJKLMNOPQRSTUVW",77 - }; - mavlink_param_value_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_value = packet_in.param_value; - packet1.param_count = packet_in.param_count; - packet1.param_index = packet_in.param_index; - packet1.param_type = packet_in.param_type; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_value_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_value_pack(system_id, component_id, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_count , packet1.param_index ); - mavlink_msg_param_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_value_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_count , packet1.param_index ); - mavlink_msg_param_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_SET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_set_t packet_in = { - 17.0,17,84,"GHIJKLMNOPQRSTU",199 - }; - mavlink_param_set_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_value = packet_in.param_value; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.param_type = packet_in.param_type; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_SET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_SET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_set_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_set_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type ); - mavlink_msg_param_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_set_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type ); - mavlink_msg_param_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_RAW_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_raw_int_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,18275,18379,18483,18587,89,156 - }; - mavlink_gps_raw_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.eph = packet_in.eph; - packet1.epv = packet_in.epv; - packet1.vel = packet_in.vel; - packet1.cog = packet_in.cog; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_raw_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_raw_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_raw_int_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible ); - mavlink_msg_gps_raw_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible ); - mavlink_msg_gps_raw_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_status_t packet_in = { - 5,{ 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91 },{ 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151 },{ 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211 },{ 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 },{ 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75 } - }; - mavlink_gps_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.satellites_visible = packet_in.satellites_visible; - - mav_array_memcpy(packet1.satellite_prn, packet_in.satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_used, packet_in.satellite_used, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_elevation, packet_in.satellite_elevation, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_azimuth, packet_in.satellite_azimuth, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_snr, packet_in.satellite_snr, sizeof(uint8_t)*20); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_status_pack(system_id, component_id, &msg , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr ); - mavlink_msg_gps_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr ); - mavlink_msg_gps_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_IMU >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_imu_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275 - }; - mavlink_scaled_imu_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - 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; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RAW_IMU >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_raw_imu_t packet_in = { - 93372036854775807ULL,17651,17755,17859,17963,18067,18171,18275,18379,18483 - }; - mavlink_raw_imu_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - 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; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RAW_IMU_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_IMU_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_imu_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_raw_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_imu_pack(system_id, component_id, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_raw_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_raw_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RAW_PRESSURE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_raw_pressure_t packet_in = { - 93372036854775807ULL,17651,17755,17859,17963 - }; - mavlink_raw_pressure_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff1 = packet_in.press_diff1; - packet1.press_diff2 = packet_in.press_diff2; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_pressure_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_raw_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_pressure_pack(system_id, component_id, &msg , packet1.time_usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature ); - mavlink_msg_raw_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_pressure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature ); - mavlink_msg_raw_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_PRESSURE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_pressure_t packet_in = { - 963497464,45.0,73.0,17859 - }; - mavlink_scaled_pressure_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff = packet_in.press_diff; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0 - }; - mavlink_attitude_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed ); - mavlink_msg_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed ); - mavlink_msg_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE_QUATERNION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_quaternion_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0 - }; - mavlink_attitude_quaternion_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.q1 = packet_in.q1; - packet1.q2 = packet_in.q2; - packet1.q3 = packet_in.q3; - packet1.q4 = packet_in.q4; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed ); - mavlink_msg_attitude_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed ); - mavlink_msg_attitude_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOCAL_POSITION_NED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_local_position_ned_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0 - }; - mavlink_local_position_ned_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_local_position_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz ); - mavlink_msg_local_position_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz ); - mavlink_msg_local_position_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GLOBAL_POSITION_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_global_position_int_t packet_in = { - 963497464,963497672,963497880,963498088,963498296,18275,18379,18483,18587 - }; - mavlink_global_position_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.relative_alt = packet_in.relative_alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.hdg = packet_in.hdg; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_global_position_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg ); - mavlink_msg_global_position_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg ); - mavlink_msg_global_position_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS_SCALED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_scaled_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65,132 - }; - mavlink_rc_channels_scaled_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.chan1_scaled = packet_in.chan1_scaled; - packet1.chan2_scaled = packet_in.chan2_scaled; - packet1.chan3_scaled = packet_in.chan3_scaled; - packet1.chan4_scaled = packet_in.chan4_scaled; - packet1.chan5_scaled = packet_in.chan5_scaled; - packet1.chan6_scaled = packet_in.chan6_scaled; - packet1.chan7_scaled = packet_in.chan7_scaled; - packet1.chan8_scaled = packet_in.chan8_scaled; - packet1.port = packet_in.port; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_scaled_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_scaled_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_scaled_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi ); - mavlink_msg_rc_channels_scaled_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi ); - mavlink_msg_rc_channels_scaled_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_raw_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65,132 - }; - mavlink_rc_channels_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.port = packet_in.port; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_raw_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi ); - mavlink_msg_rc_channels_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi ); - mavlink_msg_rc_channels_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SERVO_OUTPUT_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_servo_output_raw_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65 - }; - mavlink_servo_output_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.servo1_raw = packet_in.servo1_raw; - packet1.servo2_raw = packet_in.servo2_raw; - packet1.servo3_raw = packet_in.servo3_raw; - packet1.servo4_raw = packet_in.servo4_raw; - packet1.servo5_raw = packet_in.servo5_raw; - packet1.servo6_raw = packet_in.servo6_raw; - packet1.servo7_raw = packet_in.servo7_raw; - packet1.servo8_raw = packet_in.servo8_raw; - packet1.port = packet_in.port; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_servo_output_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_servo_output_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_servo_output_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw ); - mavlink_msg_servo_output_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw ); - mavlink_msg_servo_output_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_partial_list_t packet_in = { - 17235,17339,17,84 - }; - mavlink_mission_request_partial_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.start_index = packet_in.start_index; - packet1.end_index = packet_in.end_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_partial_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_partial_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index ); - mavlink_msg_mission_request_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index ); - mavlink_msg_mission_request_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_write_partial_list_t packet_in = { - 17235,17339,17,84 - }; - mavlink_mission_write_partial_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.start_index = packet_in.start_index; - packet1.end_index = packet_in.end_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_write_partial_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_write_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_write_partial_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index ); - mavlink_msg_mission_write_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index ); - mavlink_msg_mission_write_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ITEM >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_item_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,18691,18795,101,168,235,46,113 - }; - mavlink_mission_item_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.seq = packet_in.seq; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - packet1.current = packet_in.current; - packet1.autocontinue = packet_in.autocontinue; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_item_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z ); - mavlink_msg_mission_item_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z ); - mavlink_msg_mission_item_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_t packet_in = { - 17235,139,206 - }; - mavlink_mission_request_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq ); - mavlink_msg_mission_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq ); - mavlink_msg_mission_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_SET_CURRENT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_set_current_t packet_in = { - 17235,139,206 - }; - mavlink_mission_set_current_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_set_current_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_set_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_set_current_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq ); - mavlink_msg_mission_set_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_set_current_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq ); - mavlink_msg_mission_set_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_CURRENT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_current_t packet_in = { - 17235 - }; - mavlink_mission_current_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_current_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_current_pack(system_id, component_id, &msg , packet1.seq ); - mavlink_msg_mission_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_current_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seq ); - mavlink_msg_mission_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_list_t packet_in = { - 5,72 - }; - mavlink_mission_request_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_mission_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_mission_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_COUNT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_count_t packet_in = { - 17235,139,206 - }; - mavlink_mission_count_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.count = packet_in.count; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_count_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_count_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_count_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.count ); - mavlink_msg_mission_count_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_count_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.count ); - mavlink_msg_mission_count_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_CLEAR_ALL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_clear_all_t packet_in = { - 5,72 - }; - mavlink_mission_clear_all_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_clear_all_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_clear_all_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_clear_all_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_mission_clear_all_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_mission_clear_all_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ITEM_REACHED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_item_reached_t packet_in = { - 17235 - }; - mavlink_mission_item_reached_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_reached_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_item_reached_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_reached_pack(system_id, component_id, &msg , packet1.seq ); - mavlink_msg_mission_item_reached_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seq ); - mavlink_msg_mission_item_reached_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_ack_t packet_in = { - 5,72,139 - }; - mavlink_mission_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.type = packet_in.type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_ack_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.type ); - mavlink_msg_mission_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.type ); - mavlink_msg_mission_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_gps_global_origin_t packet_in = { - 963497464,963497672,963497880,41 - }; - mavlink_set_gps_global_origin_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - packet1.target_system = packet_in.target_system; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_gps_global_origin_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_gps_global_origin_pack(system_id, component_id, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude ); - mavlink_msg_set_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_gps_global_origin_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude ); - mavlink_msg_set_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_global_origin_t packet_in = { - 963497464,963497672,963497880 - }; - mavlink_gps_global_origin_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_global_origin_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_global_origin_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.altitude ); - mavlink_msg_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.altitude ); - mavlink_msg_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_MAP_RC >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_map_rc_t packet_in = { - 17.0,45.0,73.0,101.0,18067,187,254,"UVWXYZABCDEFGHI",113 - }; - mavlink_param_map_rc_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_value0 = packet_in.param_value0; - packet1.scale = packet_in.scale; - packet1.param_value_min = packet_in.param_value_min; - packet1.param_value_max = packet_in.param_value_max; - packet1.param_index = packet_in.param_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.parameter_rc_channel_index = packet_in.parameter_rc_channel_index; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_map_rc_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_map_rc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_map_rc_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index , packet1.parameter_rc_channel_index , packet1.param_value0 , packet1.scale , packet1.param_value_min , packet1.param_value_max ); - mavlink_msg_param_map_rc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_map_rc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index , packet1.parameter_rc_channel_index , packet1.param_value0 , packet1.scale , packet1.param_value_min , packet1.param_value_max ); - mavlink_msg_param_map_rc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_int_t packet_in = { - 17235,139,206 - }; - mavlink_mission_request_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_int_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq ); - mavlink_msg_mission_request_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq ); - mavlink_msg_mission_request_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_safety_set_allowed_area_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,77,144,211 - }; - mavlink_safety_set_allowed_area_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.p1x = packet_in.p1x; - packet1.p1y = packet_in.p1y; - packet1.p1z = packet_in.p1z; - packet1.p2x = packet_in.p2x; - packet1.p2y = packet_in.p2y; - packet1.p2z = packet_in.p2z; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_set_allowed_area_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_safety_allowed_area_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,77 - }; - mavlink_safety_allowed_area_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.p1x = packet_in.p1x; - packet1.p1y = packet_in.p1y; - packet1.p1z = packet_in.p1z; - packet1.p2x = packet_in.p2x; - packet1.p2y = packet_in.p2y; - packet1.p2z = packet_in.p2z; - packet1.frame = packet_in.frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_allowed_area_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_safety_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_allowed_area_pack(system_id, component_id, &msg , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_quaternion_cov_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0 },185.0,213.0,241.0,{ 269.0, 270.0, 271.0, 272.0, 273.0, 274.0, 275.0, 276.0, 277.0 } - }; - mavlink_attitude_quaternion_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*9); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.q , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.covariance ); - mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.q , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.covariance ); - mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_nav_controller_output_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,18275,18379,18483 - }; - mavlink_nav_controller_output_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.nav_roll = packet_in.nav_roll; - packet1.nav_pitch = packet_in.nav_pitch; - packet1.alt_error = packet_in.alt_error; - packet1.aspd_error = packet_in.aspd_error; - packet1.xtrack_error = packet_in.xtrack_error; - packet1.nav_bearing = packet_in.nav_bearing; - packet1.target_bearing = packet_in.target_bearing; - packet1.wp_dist = packet_in.wp_dist; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_nav_controller_output_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_nav_controller_output_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_nav_controller_output_pack(system_id, component_id, &msg , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error ); - mavlink_msg_nav_controller_output_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error ); - mavlink_msg_nav_controller_output_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_global_position_int_cov_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,963498504,185.0,213.0,241.0,{ 269.0, 270.0, 271.0, 272.0, 273.0, 274.0, 275.0, 276.0, 277.0, 278.0, 279.0, 280.0, 281.0, 282.0, 283.0, 284.0, 285.0, 286.0, 287.0, 288.0, 289.0, 290.0, 291.0, 292.0, 293.0, 294.0, 295.0, 296.0, 297.0, 298.0, 299.0, 300.0, 301.0, 302.0, 303.0, 304.0 },33 - }; - mavlink_global_position_int_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.relative_alt = packet_in.relative_alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.estimator_type = packet_in.estimator_type; - - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*36); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_global_position_int_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.estimator_type , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.covariance ); - mavlink_msg_global_position_int_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.estimator_type , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.covariance ); - mavlink_msg_global_position_int_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_local_position_ned_cov_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,{ 325.0, 326.0, 327.0, 328.0, 329.0, 330.0, 331.0, 332.0, 333.0, 334.0, 335.0, 336.0, 337.0, 338.0, 339.0, 340.0, 341.0, 342.0, 343.0, 344.0, 345.0, 346.0, 347.0, 348.0, 349.0, 350.0, 351.0, 352.0, 353.0, 354.0, 355.0, 356.0, 357.0, 358.0, 359.0, 360.0, 361.0, 362.0, 363.0, 364.0, 365.0, 366.0, 367.0, 368.0, 369.0 },165 - }; - mavlink_local_position_ned_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.ax = packet_in.ax; - packet1.ay = packet_in.ay; - packet1.az = packet_in.az; - packet1.estimator_type = packet_in.estimator_type; - - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*45); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_local_position_ned_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.estimator_type , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az , packet1.covariance ); - mavlink_msg_local_position_ned_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.estimator_type , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az , packet1.covariance ); - mavlink_msg_local_position_ned_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275,18379,18483,18587,18691,18795,18899,19003,19107,19211,125,192 - }; - mavlink_rc_channels_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.chan9_raw = packet_in.chan9_raw; - packet1.chan10_raw = packet_in.chan10_raw; - packet1.chan11_raw = packet_in.chan11_raw; - packet1.chan12_raw = packet_in.chan12_raw; - packet1.chan13_raw = packet_in.chan13_raw; - packet1.chan14_raw = packet_in.chan14_raw; - packet1.chan15_raw = packet_in.chan15_raw; - packet1.chan16_raw = packet_in.chan16_raw; - packet1.chan17_raw = packet_in.chan17_raw; - packet1.chan18_raw = packet_in.chan18_raw; - packet1.chancount = packet_in.chancount; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.chancount , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.chan13_raw , packet1.chan14_raw , packet1.chan15_raw , packet1.chan16_raw , packet1.chan17_raw , packet1.chan18_raw , packet1.rssi ); - mavlink_msg_rc_channels_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.chancount , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.chan13_raw , packet1.chan14_raw , packet1.chan15_raw , packet1.chan16_raw , packet1.chan17_raw , packet1.chan18_raw , packet1.rssi ); - mavlink_msg_rc_channels_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_REQUEST_DATA_STREAM >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_request_data_stream_t packet_in = { - 17235,139,206,17,84 - }; - mavlink_request_data_stream_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.req_message_rate = packet_in.req_message_rate; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.req_stream_id = packet_in.req_stream_id; - packet1.start_stop = packet_in.start_stop; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_data_stream_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_request_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_data_stream_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop ); - mavlink_msg_request_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_data_stream_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop ); - mavlink_msg_request_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DATA_STREAM >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_data_stream_t packet_in = { - 17235,139,206 - }; - mavlink_data_stream_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.message_rate = packet_in.message_rate; - packet1.stream_id = packet_in.stream_id; - packet1.on_off = packet_in.on_off; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_stream_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_stream_pack(system_id, component_id, &msg , packet1.stream_id , packet1.message_rate , packet1.on_off ); - mavlink_msg_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_stream_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.stream_id , packet1.message_rate , packet1.on_off ); - mavlink_msg_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MANUAL_CONTROL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_manual_control_t packet_in = { - 17235,17339,17443,17547,17651,163 - }; - mavlink_manual_control_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.r = packet_in.r; - packet1.buttons = packet_in.buttons; - packet1.target = packet_in.target; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_control_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_control_pack(system_id, component_id, &msg , packet1.target , packet1.x , packet1.y , packet1.z , packet1.r , packet1.buttons ); - mavlink_msg_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target , packet1.x , packet1.y , packet1.z , packet1.r , packet1.buttons ); - mavlink_msg_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_override_t packet_in = { - 17235,17339,17443,17547,17651,17755,17859,17963,53,120 - }; - mavlink_rc_channels_override_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_override_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_override_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_override_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw ); - mavlink_msg_rc_channels_override_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw ); - mavlink_msg_rc_channels_override_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ITEM_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_item_int_t packet_in = { - 17.0,45.0,73.0,101.0,963498296,963498504,185.0,18691,18795,101,168,235,46,113 - }; - mavlink_mission_item_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.seq = packet_in.seq; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - packet1.current = packet_in.current; - packet1.autocontinue = packet_in.autocontinue; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_item_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_int_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z ); - mavlink_msg_mission_item_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z ); - mavlink_msg_mission_item_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VFR_HUD >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vfr_hud_t packet_in = { - 17.0,45.0,73.0,101.0,18067,18171 - }; - mavlink_vfr_hud_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.airspeed = packet_in.airspeed; - packet1.groundspeed = packet_in.groundspeed; - packet1.alt = packet_in.alt; - packet1.climb = packet_in.climb; - packet1.heading = packet_in.heading; - packet1.throttle = packet_in.throttle; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VFR_HUD_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VFR_HUD_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vfr_hud_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vfr_hud_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vfr_hud_pack(system_id, component_id, &msg , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb ); - mavlink_msg_vfr_hud_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vfr_hud_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb ); - mavlink_msg_vfr_hud_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMMAND_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_command_int_t packet_in = { - 17.0,45.0,73.0,101.0,963498296,963498504,185.0,18691,223,34,101,168,235 - }; - mavlink_command_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - packet1.current = packet_in.current; - packet1.autocontinue = packet_in.autocontinue; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_command_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_int_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z ); - mavlink_msg_command_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z ); - mavlink_msg_command_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMMAND_LONG >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_command_long_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,18691,223,34,101 - }; - mavlink_command_long_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.param5 = packet_in.param5; - packet1.param6 = packet_in.param6; - packet1.param7 = packet_in.param7; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.confirmation = packet_in.confirmation; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_long_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_command_long_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_long_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.param5 , packet1.param6 , packet1.param7 ); - mavlink_msg_command_long_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_long_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.param5 , packet1.param6 , packet1.param7 ); - mavlink_msg_command_long_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMMAND_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_command_ack_t packet_in = { - 17235,139 - }; - mavlink_command_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.command = packet_in.command; - packet1.result = packet_in.result; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_command_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_ack_pack(system_id, component_id, &msg , packet1.command , packet1.result ); - mavlink_msg_command_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command , packet1.result ); - mavlink_msg_command_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MANUAL_SETPOINT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_manual_setpoint_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,65,132 - }; - mavlink_manual_setpoint_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.thrust = packet_in.thrust; - packet1.mode_switch = packet_in.mode_switch; - packet1.manual_override_switch = packet_in.manual_override_switch; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_setpoint_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_manual_setpoint_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_setpoint_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch ); - mavlink_msg_manual_setpoint_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch ); - mavlink_msg_manual_setpoint_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_ATTITUDE_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_attitude_target_t packet_in = { - 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,241.0,113,180,247 - }; - mavlink_set_attitude_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.body_roll_rate = packet_in.body_roll_rate; - packet1.body_pitch_rate = packet_in.body_pitch_rate; - packet1.body_yaw_rate = packet_in.body_yaw_rate; - packet1.thrust = packet_in.thrust; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.type_mask = packet_in.type_mask; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_attitude_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_attitude_target_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); - mavlink_msg_set_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_attitude_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); - mavlink_msg_set_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_target_t packet_in = { - 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,241.0,113 - }; - mavlink_attitude_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.body_roll_rate = packet_in.body_roll_rate; - packet1.body_pitch_rate = packet_in.body_pitch_rate; - packet1.body_yaw_rate = packet_in.body_yaw_rate; - packet1.thrust = packet_in.thrust; - packet1.type_mask = packet_in.type_mask; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_target_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); - mavlink_msg_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); - mavlink_msg_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_position_target_local_ned_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27,94,161 - }; - mavlink_set_position_target_local_ned_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_local_ned_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_position_target_local_ned_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27 - }; - mavlink_position_target_local_ned_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_local_ned_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_position_target_global_int_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27,94,161 - }; - mavlink_set_position_target_global_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat_int = packet_in.lat_int; - packet1.lon_int = packet_in.lon_int; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_global_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_position_target_global_int_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27 - }; - mavlink_position_target_global_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat_int = packet_in.lat_int; - packet1.lon_int = packet_in.lon_int; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_global_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_local_position_ned_system_global_offset_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0 - }; - mavlink_local_position_ned_system_global_offset_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_system_global_offset_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_state_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,963499128,963499336,963499544,19523,19627,19731,19835,19939,20043 - }; - mavlink_hil_state_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.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_pack(system_id, component_id, &msg , packet1.time_usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_CONTROLS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_controls_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,125,192 - }; - mavlink_hil_controls_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.roll_ailerons = packet_in.roll_ailerons; - packet1.pitch_elevator = packet_in.pitch_elevator; - packet1.yaw_rudder = packet_in.yaw_rudder; - packet1.throttle = packet_in.throttle; - packet1.aux1 = packet_in.aux1; - packet1.aux2 = packet_in.aux2; - packet1.aux3 = packet_in.aux3; - packet1.aux4 = packet_in.aux4; - packet1.mode = packet_in.mode; - packet1.nav_mode = packet_in.nav_mode; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_controls_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_controls_pack(system_id, component_id, &msg , packet1.time_usec , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.aux1 , packet1.aux2 , packet1.aux3 , packet1.aux4 , packet1.mode , packet1.nav_mode ); - mavlink_msg_hil_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_controls_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.aux1 , packet1.aux2 , packet1.aux3 , packet1.aux4 , packet1.mode , packet1.nav_mode ); - mavlink_msg_hil_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_rc_inputs_raw_t packet_in = { - 93372036854775807ULL,17651,17755,17859,17963,18067,18171,18275,18379,18483,18587,18691,18795,101 - }; - mavlink_hil_rc_inputs_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.chan9_raw = packet_in.chan9_raw; - packet1.chan10_raw = packet_in.chan10_raw; - packet1.chan11_raw = packet_in.chan11_raw; - packet1.chan12_raw = packet_in.chan12_raw; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_rc_inputs_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.rssi ); - mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.rssi ); - mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_actuator_controls_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,{ 129.0, 130.0, 131.0, 132.0, 133.0, 134.0, 135.0, 136.0, 137.0, 138.0, 139.0, 140.0, 141.0, 142.0, 143.0, 144.0 },245 - }; - mavlink_hil_actuator_controls_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.flags = packet_in.flags; - packet1.mode = packet_in.mode; - - mav_array_memcpy(packet1.controls, packet_in.controls, sizeof(float)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_actuator_controls_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_actuator_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_actuator_controls_pack(system_id, component_id, &msg , packet1.time_usec , packet1.controls , packet1.mode , packet1.flags ); - mavlink_msg_hil_actuator_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_actuator_controls_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.controls , packet1.mode , packet1.flags ); - mavlink_msg_hil_actuator_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPTICAL_FLOW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_optical_flow_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,18275,18379,77,144 - }; - mavlink_optical_flow_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.flow_comp_m_x = packet_in.flow_comp_m_x; - packet1.flow_comp_m_y = packet_in.flow_comp_m_y; - packet1.ground_distance = packet_in.ground_distance; - packet1.flow_x = packet_in.flow_x; - packet1.flow_y = packet_in.flow_y; - packet1.sensor_id = packet_in.sensor_id; - packet1.quality = packet_in.quality; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance ); - mavlink_msg_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance ); - mavlink_msg_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_global_vision_position_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0 - }; - mavlink_global_vision_position_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_vision_position_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vision_position_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0 - }; - mavlink_vision_position_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vision_speed_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0 - }; - mavlink_vision_speed_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_speed_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vision_speed_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_speed_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z ); - mavlink_msg_vision_speed_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z ); - mavlink_msg_vision_speed_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vicon_position_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0 - }; - mavlink_vicon_position_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vicon_position_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vicon_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vicon_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_vicon_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_vicon_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIGHRES_IMU >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_highres_imu_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,20355 - }; - mavlink_highres_imu_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - 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.temperature = packet_in.temperature; - packet1.fields_updated = packet_in.fields_updated; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_highres_imu_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_highres_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_highres_imu_pack(system_id, component_id, &msg , packet1.time_usec , 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.temperature , packet1.fields_updated ); - mavlink_msg_highres_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_highres_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , 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.temperature , packet1.fields_updated ); - mavlink_msg_highres_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPTICAL_FLOW_RAD >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_optical_flow_rad_t packet_in = { - 93372036854775807ULL,963497880,101.0,129.0,157.0,185.0,213.0,963499128,269.0,19315,3,70 - }; - mavlink_optical_flow_rad_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.integration_time_us = packet_in.integration_time_us; - packet1.integrated_x = packet_in.integrated_x; - packet1.integrated_y = packet_in.integrated_y; - packet1.integrated_xgyro = packet_in.integrated_xgyro; - packet1.integrated_ygyro = packet_in.integrated_ygyro; - packet1.integrated_zgyro = packet_in.integrated_zgyro; - packet1.time_delta_distance_us = packet_in.time_delta_distance_us; - packet1.distance = packet_in.distance; - packet1.temperature = packet_in.temperature; - packet1.sensor_id = packet_in.sensor_id; - packet1.quality = packet_in.quality; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_rad_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_optical_flow_rad_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_rad_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_optical_flow_rad_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_rad_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_optical_flow_rad_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_SENSOR >= 256) { - return; - } -#endif - 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,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,963500584 - }; - mavlink_hil_sensor_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - 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.temperature = packet_in.temperature; - packet1.fields_updated = packet_in.fields_updated; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN); - } -#endif - 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.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.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.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.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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SIM_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_sim_state_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,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 - }; - mavlink_sim_state_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.q1 = packet_in.q1; - packet1.q2 = packet_in.q2; - packet1.q3 = packet_in.q3; - packet1.q4 = packet_in.q4; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - 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.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.std_dev_horz = packet_in.std_dev_horz; - packet1.std_dev_vert = packet_in.std_dev_vert; - packet1.vn = packet_in.vn; - packet1.ve = packet_in.ve; - packet1.vd = packet_in.vd; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SIM_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SIM_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sim_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_sim_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sim_state_pack(system_id, component_id, &msg , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.lat , packet1.lon , packet1.alt , packet1.std_dev_horz , packet1.std_dev_vert , packet1.vn , packet1.ve , packet1.vd ); - mavlink_msg_sim_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sim_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.lat , packet1.lon , packet1.alt , packet1.std_dev_horz , packet1.std_dev_vert , packet1.vn , packet1.ve , packet1.vd ); - mavlink_msg_sim_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RADIO_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_radio_status_t packet_in = { - 17235,17339,17,84,151,218,29 - }; - mavlink_radio_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.rxerrors = packet_in.rxerrors; - packet1.fixed = packet_in.fixed; - packet1.rssi = packet_in.rssi; - packet1.remrssi = packet_in.remrssi; - packet1.txbuf = packet_in.txbuf; - packet1.noise = packet_in.noise; - packet1.remnoise = packet_in.remnoise; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_radio_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_radio_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_radio_status_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed ); - mavlink_msg_radio_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_radio_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed ); - mavlink_msg_radio_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_file_transfer_protocol_t packet_in = { - 5,72,139,{ 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200 } - }; - mavlink_file_transfer_protocol_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_network = packet_in.target_network; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.payload, packet_in.payload, sizeof(uint8_t)*251); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_file_transfer_protocol_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_file_transfer_protocol_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_file_transfer_protocol_pack(system_id, component_id, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.payload ); - mavlink_msg_file_transfer_protocol_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.payload ); - mavlink_msg_file_transfer_protocol_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TIMESYNC >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_timesync_t packet_in = { - 93372036854775807LL,93372036854776311LL - }; - mavlink_timesync_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.tc1 = packet_in.tc1; - packet1.ts1 = packet_in.ts1; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TIMESYNC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TIMESYNC_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_timesync_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_timesync_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_timesync_pack(system_id, component_id, &msg , packet1.tc1 , packet1.ts1 ); - mavlink_msg_timesync_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_timesync_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.tc1 , packet1.ts1 ); - mavlink_msg_timesync_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_TRIGGER >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_trigger_t packet_in = { - 93372036854775807ULL,963497880 - }; - mavlink_camera_trigger_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.seq = packet_in.seq; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_trigger_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_trigger_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_trigger_pack(system_id, component_id, &msg , packet1.time_usec , packet1.seq ); - mavlink_msg_camera_trigger_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_trigger_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.seq ); - mavlink_msg_camera_trigger_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_GPS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_gps_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,18275,18379,18483,18587,18691,18795,18899,235,46 - }; - mavlink_hil_gps_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.eph = packet_in.eph; - packet1.epv = packet_in.epv; - packet1.vel = packet_in.vel; - packet1.vn = packet_in.vn; - packet1.ve = packet_in.ve; - packet1.vd = packet_in.vd; - packet1.cog = packet_in.cog; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_GPS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_GPS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_gps_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_gps_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_gps_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.vn , packet1.ve , packet1.vd , packet1.cog , packet1.satellites_visible ); - mavlink_msg_hil_gps_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_gps_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.vn , packet1.ve , packet1.vd , packet1.cog , packet1.satellites_visible ); - mavlink_msg_hil_gps_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_OPTICAL_FLOW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_optical_flow_t packet_in = { - 93372036854775807ULL,963497880,101.0,129.0,157.0,185.0,213.0,963499128,269.0,19315,3,70 - }; - mavlink_hil_optical_flow_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.integration_time_us = packet_in.integration_time_us; - packet1.integrated_x = packet_in.integrated_x; - packet1.integrated_y = packet_in.integrated_y; - packet1.integrated_xgyro = packet_in.integrated_xgyro; - packet1.integrated_ygyro = packet_in.integrated_ygyro; - packet1.integrated_zgyro = packet_in.integrated_zgyro; - packet1.time_delta_distance_us = packet_in.time_delta_distance_us; - packet1.distance = packet_in.distance; - packet1.temperature = packet_in.temperature; - packet1.sensor_id = packet_in.sensor_id; - packet1.quality = packet_in.quality; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_optical_flow_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_hil_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_hil_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_STATE_QUATERNION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_state_quaternion_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0 },185.0,213.0,241.0,963499336,963499544,963499752,19731,19835,19939,20043,20147,20251,20355,20459 - }; - mavlink_hil_state_quaternion_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.ind_airspeed = packet_in.ind_airspeed; - packet1.true_airspeed = packet_in.true_airspeed; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - - mav_array_memcpy(packet1.attitude_quaternion, packet_in.attitude_quaternion, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_quaternion_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_state_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_quaternion_pack(system_id, component_id, &msg , packet1.time_usec , packet1.attitude_quaternion , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.ind_airspeed , packet1.true_airspeed , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.attitude_quaternion , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.ind_airspeed , packet1.true_airspeed , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_IMU2 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_imu2_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275 - }; - mavlink_scaled_imu2_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - 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; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu2_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_imu2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu2_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_REQUEST_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_request_list_t packet_in = { - 17235,17339,17,84 - }; - mavlink_log_request_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.start = packet_in.start; - packet1.end = packet_in.end; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.start , packet1.end ); - mavlink_msg_log_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.start , packet1.end ); - mavlink_msg_log_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_ENTRY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_entry_t packet_in = { - 963497464,963497672,17651,17755,17859 - }; - mavlink_log_entry_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_utc = packet_in.time_utc; - packet1.size = packet_in.size; - packet1.id = packet_in.id; - packet1.num_logs = packet_in.num_logs; - packet1.last_log_num = packet_in.last_log_num; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_entry_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_entry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_entry_pack(system_id, component_id, &msg , packet1.id , packet1.num_logs , packet1.last_log_num , packet1.time_utc , packet1.size ); - mavlink_msg_log_entry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_entry_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.num_logs , packet1.last_log_num , packet1.time_utc , packet1.size ); - mavlink_msg_log_entry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_REQUEST_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_request_data_t packet_in = { - 963497464,963497672,17651,163,230 - }; - mavlink_log_request_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.ofs = packet_in.ofs; - packet1.count = packet_in.count; - packet1.id = packet_in.id; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_request_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_data_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id , packet1.ofs , packet1.count ); - mavlink_msg_log_request_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id , packet1.ofs , packet1.count ); - mavlink_msg_log_request_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_data_t packet_in = { - 963497464,17443,151,{ 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51 } - }; - mavlink_log_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.ofs = packet_in.ofs; - packet1.id = packet_in.id; - packet1.count = packet_in.count; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*90); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_data_pack(system_id, component_id, &msg , packet1.id , packet1.ofs , packet1.count , packet1.data ); - mavlink_msg_log_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.ofs , packet1.count , packet1.data ); - mavlink_msg_log_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_ERASE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_erase_t packet_in = { - 5,72 - }; - mavlink_log_erase_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_erase_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_erase_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_erase_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_erase_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_erase_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_erase_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_REQUEST_END >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_request_end_t packet_in = { - 5,72 - }; - mavlink_log_request_end_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_end_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_request_end_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_end_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_request_end_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_end_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_request_end_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_INJECT_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_inject_data_t packet_in = { - 5,72,139,{ 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59 } - }; - mavlink_gps_inject_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.len = packet_in.len; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*110); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_inject_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_inject_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_inject_data_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.len , packet1.data ); - mavlink_msg_gps_inject_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.len , packet1.data ); - mavlink_msg_gps_inject_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS2_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps2_raw_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,963498504,18483,18587,18691,18795,101,168,235 - }; - mavlink_gps2_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.dgps_age = packet_in.dgps_age; - packet1.eph = packet_in.eph; - packet1.epv = packet_in.epv; - packet1.vel = packet_in.vel; - packet1.cog = packet_in.cog; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - packet1.dgps_numch = packet_in.dgps_numch; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps2_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.dgps_numch , packet1.dgps_age ); - mavlink_msg_gps2_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.dgps_numch , packet1.dgps_age ); - mavlink_msg_gps2_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_POWER_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_power_status_t packet_in = { - 17235,17339,17443 - }; - mavlink_power_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.Vcc = packet_in.Vcc; - packet1.Vservo = packet_in.Vservo; - packet1.flags = packet_in.flags; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_power_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_power_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_power_status_pack(system_id, component_id, &msg , packet1.Vcc , packet1.Vservo , packet1.flags ); - mavlink_msg_power_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_power_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Vcc , packet1.Vservo , packet1.flags ); - mavlink_msg_power_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SERIAL_CONTROL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_serial_control_t packet_in = { - 963497464,17443,151,218,29,{ 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165 } - }; - mavlink_serial_control_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.baudrate = packet_in.baudrate; - packet1.timeout = packet_in.timeout; - packet1.device = packet_in.device; - packet1.flags = packet_in.flags; - packet1.count = packet_in.count; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*70); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_serial_control_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_serial_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_serial_control_pack(system_id, component_id, &msg , packet1.device , packet1.flags , packet1.timeout , packet1.baudrate , packet1.count , packet1.data ); - mavlink_msg_serial_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_serial_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.device , packet1.flags , packet1.timeout , packet1.baudrate , packet1.count , packet1.data ); - mavlink_msg_serial_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_RTK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_rtk_t packet_in = { - 963497464,963497672,963497880,963498088,963498296,963498504,963498712,18691,223,34,101,168,235 - }; - mavlink_gps_rtk_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_last_baseline_ms = packet_in.time_last_baseline_ms; - packet1.tow = packet_in.tow; - packet1.baseline_a_mm = packet_in.baseline_a_mm; - packet1.baseline_b_mm = packet_in.baseline_b_mm; - packet1.baseline_c_mm = packet_in.baseline_c_mm; - packet1.accuracy = packet_in.accuracy; - packet1.iar_num_hypotheses = packet_in.iar_num_hypotheses; - packet1.wn = packet_in.wn; - packet1.rtk_receiver_id = packet_in.rtk_receiver_id; - packet1.rtk_health = packet_in.rtk_health; - packet1.rtk_rate = packet_in.rtk_rate; - packet1.nsats = packet_in.nsats; - packet1.baseline_coords_type = packet_in.baseline_coords_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_RTK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_RTK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtk_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtk_pack(system_id, component_id, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtk_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS2_RTK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps2_rtk_t packet_in = { - 963497464,963497672,963497880,963498088,963498296,963498504,963498712,18691,223,34,101,168,235 - }; - mavlink_gps2_rtk_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_last_baseline_ms = packet_in.time_last_baseline_ms; - packet1.tow = packet_in.tow; - packet1.baseline_a_mm = packet_in.baseline_a_mm; - packet1.baseline_b_mm = packet_in.baseline_b_mm; - packet1.baseline_c_mm = packet_in.baseline_c_mm; - packet1.accuracy = packet_in.accuracy; - packet1.iar_num_hypotheses = packet_in.iar_num_hypotheses; - packet1.wn = packet_in.wn; - packet1.rtk_receiver_id = packet_in.rtk_receiver_id; - packet1.rtk_health = packet_in.rtk_health; - packet1.rtk_rate = packet_in.rtk_rate; - packet1.nsats = packet_in.nsats; - packet1.baseline_coords_type = packet_in.baseline_coords_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_rtk_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps2_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_rtk_pack(system_id, component_id, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps2_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_rtk_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps2_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_IMU3 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_imu3_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275 - }; - mavlink_scaled_imu3_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - 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; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu3_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_imu3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu3_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu3_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_data_transmission_handshake_t packet_in = { - 963497464,17443,17547,17651,163,230,41 - }; - mavlink_data_transmission_handshake_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.size = packet_in.size; - packet1.width = packet_in.width; - packet1.height = packet_in.height; - packet1.packets = packet_in.packets; - packet1.type = packet_in.type; - packet1.payload = packet_in.payload; - packet1.jpg_quality = packet_in.jpg_quality; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_transmission_handshake_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_data_transmission_handshake_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_transmission_handshake_pack(system_id, component_id, &msg , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality ); - mavlink_msg_data_transmission_handshake_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality ); - mavlink_msg_data_transmission_handshake_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ENCAPSULATED_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_encapsulated_data_t packet_in = { - 17235,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135 } - }; - mavlink_encapsulated_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seqnr = packet_in.seqnr; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*253); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_encapsulated_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_encapsulated_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_encapsulated_data_pack(system_id, component_id, &msg , packet1.seqnr , packet1.data ); - mavlink_msg_encapsulated_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seqnr , packet1.data ); - mavlink_msg_encapsulated_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DISTANCE_SENSOR >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_distance_sensor_t packet_in = { - 963497464,17443,17547,17651,163,230,41,108 - }; - mavlink_distance_sensor_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.min_distance = packet_in.min_distance; - packet1.max_distance = packet_in.max_distance; - packet1.current_distance = packet_in.current_distance; - packet1.type = packet_in.type; - packet1.id = packet_in.id; - packet1.orientation = packet_in.orientation; - packet1.covariance = packet_in.covariance; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_distance_sensor_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_distance_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_distance_sensor_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.min_distance , packet1.max_distance , packet1.current_distance , packet1.type , packet1.id , packet1.orientation , packet1.covariance ); - mavlink_msg_distance_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_distance_sensor_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.min_distance , packet1.max_distance , packet1.current_distance , packet1.type , packet1.id , packet1.orientation , packet1.covariance ); - mavlink_msg_distance_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_REQUEST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_request_t packet_in = { - 93372036854775807ULL,963497880,963498088,18067 - }; - mavlink_terrain_request_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.mask = packet_in.mask; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.grid_spacing = packet_in.grid_spacing; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_request_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_request_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask ); - mavlink_msg_terrain_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask ); - mavlink_msg_terrain_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_data_t packet_in = { - 963497464,963497672,17651,{ 17755, 17756, 17757, 17758, 17759, 17760, 17761, 17762, 17763, 17764, 17765, 17766, 17767, 17768, 17769, 17770 },3 - }; - mavlink_terrain_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.grid_spacing = packet_in.grid_spacing; - packet1.gridbit = packet_in.gridbit; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(int16_t)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_data_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data ); - mavlink_msg_terrain_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data ); - mavlink_msg_terrain_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_CHECK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_check_t packet_in = { - 963497464,963497672 - }; - mavlink_terrain_check_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_check_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_check_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_check_pack(system_id, component_id, &msg , packet1.lat , packet1.lon ); - mavlink_msg_terrain_check_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_check_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon ); - mavlink_msg_terrain_check_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_REPORT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_report_t packet_in = { - 963497464,963497672,73.0,101.0,18067,18171,18275 - }; - mavlink_terrain_report_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.terrain_height = packet_in.terrain_height; - packet1.current_height = packet_in.current_height; - packet1.spacing = packet_in.spacing; - packet1.pending = packet_in.pending; - packet1.loaded = packet_in.loaded; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_report_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_report_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.spacing , packet1.terrain_height , packet1.current_height , packet1.pending , packet1.loaded ); - mavlink_msg_terrain_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.spacing , packet1.terrain_height , packet1.current_height , packet1.pending , packet1.loaded ); - mavlink_msg_terrain_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_PRESSURE2 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_pressure2_t packet_in = { - 963497464,45.0,73.0,17859 - }; - mavlink_scaled_pressure2_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff = packet_in.press_diff; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure2_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_pressure2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure2_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATT_POS_MOCAP >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_att_pos_mocap_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0 },185.0,213.0,241.0 - }; - mavlink_att_pos_mocap_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_att_pos_mocap_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_att_pos_mocap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_att_pos_mocap_pack(system_id, component_id, &msg , packet1.time_usec , packet1.q , packet1.x , packet1.y , packet1.z ); - mavlink_msg_att_pos_mocap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.q , packet1.x , packet1.y , packet1.z ); - mavlink_msg_att_pos_mocap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_actuator_control_target_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0, 77.0, 78.0, 79.0, 80.0 },125,192,3 - }; - mavlink_set_actuator_control_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.group_mlx = packet_in.group_mlx; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.controls, packet_in.controls, sizeof(float)*8); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_actuator_control_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_actuator_control_target_pack(system_id, component_id, &msg , packet1.time_usec , packet1.group_mlx , packet1.target_system , packet1.target_component , packet1.controls ); - mavlink_msg_set_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_actuator_control_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.group_mlx , packet1.target_system , packet1.target_component , packet1.controls ); - mavlink_msg_set_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_actuator_control_target_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0, 77.0, 78.0, 79.0, 80.0 },125 - }; - mavlink_actuator_control_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.group_mlx = packet_in.group_mlx; - - mav_array_memcpy(packet1.controls, packet_in.controls, sizeof(float)*8); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_control_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_control_target_pack(system_id, component_id, &msg , packet1.time_usec , packet1.group_mlx , packet1.controls ); - mavlink_msg_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_control_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.group_mlx , packet1.controls ); - mavlink_msg_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ALTITUDE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_altitude_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0 - }; - mavlink_altitude_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.altitude_monotonic = packet_in.altitude_monotonic; - packet1.altitude_amsl = packet_in.altitude_amsl; - packet1.altitude_local = packet_in.altitude_local; - packet1.altitude_relative = packet_in.altitude_relative; - packet1.altitude_terrain = packet_in.altitude_terrain; - packet1.bottom_clearance = packet_in.bottom_clearance; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ALTITUDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ALTITUDE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_altitude_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_altitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_altitude_pack(system_id, component_id, &msg , packet1.time_usec , packet1.altitude_monotonic , packet1.altitude_amsl , packet1.altitude_local , packet1.altitude_relative , packet1.altitude_terrain , packet1.bottom_clearance ); - mavlink_msg_altitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_altitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.altitude_monotonic , packet1.altitude_amsl , packet1.altitude_local , packet1.altitude_relative , packet1.altitude_terrain , packet1.bottom_clearance ); - mavlink_msg_altitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RESOURCE_REQUEST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_resource_request_t packet_in = { - 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2 },243,{ 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173 } - }; - mavlink_resource_request_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.request_id = packet_in.request_id; - packet1.uri_type = packet_in.uri_type; - packet1.transfer_type = packet_in.transfer_type; - - mav_array_memcpy(packet1.uri, packet_in.uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet1.storage, packet_in.storage, sizeof(uint8_t)*120); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_resource_request_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_resource_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_resource_request_pack(system_id, component_id, &msg , packet1.request_id , packet1.uri_type , packet1.uri , packet1.transfer_type , packet1.storage ); - mavlink_msg_resource_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_resource_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.request_id , packet1.uri_type , packet1.uri , packet1.transfer_type , packet1.storage ); - mavlink_msg_resource_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_PRESSURE3 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_pressure3_t packet_in = { - 963497464,45.0,73.0,17859 - }; - mavlink_scaled_pressure3_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff = packet_in.press_diff; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure3_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_pressure3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure3_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure3_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FOLLOW_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_follow_target_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,963498296,963498504,185.0,{ 213.0, 214.0, 215.0 },{ 297.0, 298.0, 299.0 },{ 381.0, 382.0, 383.0, 384.0 },{ 493.0, 494.0, 495.0 },{ 577.0, 578.0, 579.0 },25 - }; - mavlink_follow_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.timestamp = packet_in.timestamp; - packet1.custom_state = packet_in.custom_state; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.est_capabilities = packet_in.est_capabilities; - - mav_array_memcpy(packet1.vel, packet_in.vel, sizeof(float)*3); - mav_array_memcpy(packet1.acc, packet_in.acc, sizeof(float)*3); - mav_array_memcpy(packet1.attitude_q, packet_in.attitude_q, sizeof(float)*4); - mav_array_memcpy(packet1.rates, packet_in.rates, sizeof(float)*3); - mav_array_memcpy(packet1.position_cov, packet_in.position_cov, sizeof(float)*3); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_follow_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_follow_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_follow_target_pack(system_id, component_id, &msg , packet1.timestamp , packet1.est_capabilities , packet1.lat , packet1.lon , packet1.alt , packet1.vel , packet1.acc , packet1.attitude_q , packet1.rates , packet1.position_cov , packet1.custom_state ); - mavlink_msg_follow_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_follow_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.est_capabilities , packet1.lat , packet1.lon , packet1.alt , packet1.vel , packet1.acc , packet1.attitude_q , packet1.rates , packet1.position_cov , packet1.custom_state ); - mavlink_msg_follow_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_control_system_state_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,{ 353.0, 354.0, 355.0 },{ 437.0, 438.0, 439.0 },{ 521.0, 522.0, 523.0, 524.0 },633.0,661.0,689.0 - }; - mavlink_control_system_state_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x_acc = packet_in.x_acc; - packet1.y_acc = packet_in.y_acc; - packet1.z_acc = packet_in.z_acc; - packet1.x_vel = packet_in.x_vel; - packet1.y_vel = packet_in.y_vel; - packet1.z_vel = packet_in.z_vel; - packet1.x_pos = packet_in.x_pos; - packet1.y_pos = packet_in.y_pos; - packet1.z_pos = packet_in.z_pos; - packet1.airspeed = packet_in.airspeed; - packet1.roll_rate = packet_in.roll_rate; - packet1.pitch_rate = packet_in.pitch_rate; - packet1.yaw_rate = packet_in.yaw_rate; - - mav_array_memcpy(packet1.vel_variance, packet_in.vel_variance, sizeof(float)*3); - mav_array_memcpy(packet1.pos_variance, packet_in.pos_variance, sizeof(float)*3); - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_control_system_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_control_system_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_control_system_state_pack(system_id, component_id, &msg , packet1.time_usec , packet1.x_acc , packet1.y_acc , packet1.z_acc , packet1.x_vel , packet1.y_vel , packet1.z_vel , packet1.x_pos , packet1.y_pos , packet1.z_pos , packet1.airspeed , packet1.vel_variance , packet1.pos_variance , packet1.q , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate ); - mavlink_msg_control_system_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_control_system_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.x_acc , packet1.y_acc , packet1.z_acc , packet1.x_vel , packet1.y_vel , packet1.z_vel , packet1.x_pos , packet1.y_pos , packet1.z_pos , packet1.airspeed , packet1.vel_variance , packet1.pos_variance , packet1.q , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate ); - mavlink_msg_control_system_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_BATTERY_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_battery_status_t packet_in = { - 963497464,963497672,17651,{ 17755, 17756, 17757, 17758, 17759, 17760, 17761, 17762, 17763, 17764 },18795,101,168,235,46 - }; - mavlink_battery_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.current_consumed = packet_in.current_consumed; - packet1.energy_consumed = packet_in.energy_consumed; - packet1.temperature = packet_in.temperature; - packet1.current_battery = packet_in.current_battery; - packet1.id = packet_in.id; - packet1.battery_function = packet_in.battery_function; - packet1.type = packet_in.type; - packet1.battery_remaining = packet_in.battery_remaining; - - mav_array_memcpy(packet1.voltages, packet_in.voltages, sizeof(uint16_t)*10); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_battery_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_battery_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_battery_status_pack(system_id, component_id, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining ); - mavlink_msg_battery_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_battery_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining ); - mavlink_msg_battery_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AUTOPILOT_VERSION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_autopilot_version_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,963498296,963498504,963498712,963498920,18899,19003,{ 113, 114, 115, 116, 117, 118, 119, 120 },{ 137, 138, 139, 140, 141, 142, 143, 144 },{ 161, 162, 163, 164, 165, 166, 167, 168 } - }; - mavlink_autopilot_version_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.capabilities = packet_in.capabilities; - packet1.uid = packet_in.uid; - packet1.flight_sw_version = packet_in.flight_sw_version; - packet1.middleware_sw_version = packet_in.middleware_sw_version; - packet1.os_sw_version = packet_in.os_sw_version; - packet1.board_version = packet_in.board_version; - packet1.vendor_id = packet_in.vendor_id; - packet1.product_id = packet_in.product_id; - - mav_array_memcpy(packet1.flight_custom_version, packet_in.flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet1.middleware_custom_version, packet_in.middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet1.os_custom_version, packet_in.os_custom_version, sizeof(uint8_t)*8); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_version_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_autopilot_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_version_pack(system_id, component_id, &msg , packet1.capabilities , packet1.flight_sw_version , packet1.middleware_sw_version , packet1.os_sw_version , packet1.board_version , packet1.flight_custom_version , packet1.middleware_custom_version , packet1.os_custom_version , packet1.vendor_id , packet1.product_id , packet1.uid ); - mavlink_msg_autopilot_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_version_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.capabilities , packet1.flight_sw_version , packet1.middleware_sw_version , packet1.os_sw_version , packet1.board_version , packet1.flight_custom_version , packet1.middleware_custom_version , packet1.os_custom_version , packet1.vendor_id , packet1.product_id , packet1.uid ); - mavlink_msg_autopilot_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LANDING_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_landing_target_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,89,156 - }; - mavlink_landing_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.angle_x = packet_in.angle_x; - packet1.angle_y = packet_in.angle_y; - packet1.distance = packet_in.distance; - packet1.size_x = packet_in.size_x; - packet1.size_y = packet_in.size_y; - packet1.target_num = packet_in.target_num; - packet1.frame = packet_in.frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_landing_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_landing_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_landing_target_pack(system_id, component_id, &msg , packet1.time_usec , packet1.target_num , packet1.frame , packet1.angle_x , packet1.angle_y , packet1.distance , packet1.size_x , packet1.size_y ); - mavlink_msg_landing_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_landing_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.target_num , packet1.frame , packet1.angle_x , packet1.angle_y , packet1.distance , packet1.size_x , packet1.size_y ); - mavlink_msg_landing_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESTIMATOR_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_estimator_status_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,19315 - }; - mavlink_estimator_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.vel_ratio = packet_in.vel_ratio; - packet1.pos_horiz_ratio = packet_in.pos_horiz_ratio; - packet1.pos_vert_ratio = packet_in.pos_vert_ratio; - packet1.mag_ratio = packet_in.mag_ratio; - packet1.hagl_ratio = packet_in.hagl_ratio; - packet1.tas_ratio = packet_in.tas_ratio; - packet1.pos_horiz_accuracy = packet_in.pos_horiz_accuracy; - packet1.pos_vert_accuracy = packet_in.pos_vert_accuracy; - packet1.flags = packet_in.flags; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_estimator_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_estimator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_estimator_status_pack(system_id, component_id, &msg , packet1.time_usec , packet1.flags , packet1.vel_ratio , packet1.pos_horiz_ratio , packet1.pos_vert_ratio , packet1.mag_ratio , packet1.hagl_ratio , packet1.tas_ratio , packet1.pos_horiz_accuracy , packet1.pos_vert_accuracy ); - mavlink_msg_estimator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_estimator_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.flags , packet1.vel_ratio , packet1.pos_horiz_ratio , packet1.pos_vert_ratio , packet1.mag_ratio , packet1.hagl_ratio , packet1.tas_ratio , packet1.pos_horiz_accuracy , packet1.pos_vert_accuracy ); - mavlink_msg_estimator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_WIND_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_wind_cov_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0 - }; - mavlink_wind_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.wind_x = packet_in.wind_x; - packet1.wind_y = packet_in.wind_y; - packet1.wind_z = packet_in.wind_z; - packet1.var_horiz = packet_in.var_horiz; - packet1.var_vert = packet_in.var_vert; - packet1.wind_alt = packet_in.wind_alt; - packet1.horiz_accuracy = packet_in.horiz_accuracy; - packet1.vert_accuracy = packet_in.vert_accuracy; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_WIND_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WIND_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wind_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_wind_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wind_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.wind_x , packet1.wind_y , packet1.wind_z , packet1.var_horiz , packet1.var_vert , packet1.wind_alt , packet1.horiz_accuracy , packet1.vert_accuracy ); - mavlink_msg_wind_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wind_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.wind_x , packet1.wind_y , packet1.wind_z , packet1.var_horiz , packet1.var_vert , packet1.wind_alt , packet1.horiz_accuracy , packet1.vert_accuracy ); - mavlink_msg_wind_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_INPUT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_input_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,20147,20251,185,252,63 - }; - mavlink_gps_input_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.time_week_ms = packet_in.time_week_ms; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.hdop = packet_in.hdop; - packet1.vdop = packet_in.vdop; - packet1.vn = packet_in.vn; - packet1.ve = packet_in.ve; - packet1.vd = packet_in.vd; - packet1.speed_accuracy = packet_in.speed_accuracy; - packet1.horiz_accuracy = packet_in.horiz_accuracy; - packet1.vert_accuracy = packet_in.vert_accuracy; - packet1.ignore_flags = packet_in.ignore_flags; - packet1.time_week = packet_in.time_week; - packet1.gps_id = packet_in.gps_id; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_input_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_input_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_input_pack(system_id, component_id, &msg , packet1.time_usec , packet1.gps_id , packet1.ignore_flags , packet1.time_week_ms , packet1.time_week , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.hdop , packet1.vdop , packet1.vn , packet1.ve , packet1.vd , packet1.speed_accuracy , packet1.horiz_accuracy , packet1.vert_accuracy , packet1.satellites_visible ); - mavlink_msg_gps_input_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_input_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.gps_id , packet1.ignore_flags , packet1.time_week_ms , packet1.time_week , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.hdop , packet1.vdop , packet1.vn , packet1.ve , packet1.vd , packet1.speed_accuracy , packet1.horiz_accuracy , packet1.vert_accuracy , packet1.satellites_visible ); - mavlink_msg_gps_input_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_RTCM_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_rtcm_data_t packet_in = { - 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62 } - }; - mavlink_gps_rtcm_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.flags = packet_in.flags; - packet1.len = packet_in.len; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*180); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtcm_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_rtcm_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtcm_data_pack(system_id, component_id, &msg , packet1.flags , packet1.len , packet1.data ); - mavlink_msg_gps_rtcm_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtcm_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.flags , packet1.len , packet1.data ); - mavlink_msg_gps_rtcm_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIGH_LATENCY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_high_latency_t packet_in = { - 963497464,963497672,963497880,17859,17963,18067,18171,18275,18379,18483,211,22,89,156,223,34,101,168,235,46,113,180,247,58 - }; - mavlink_high_latency_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.custom_mode = packet_in.custom_mode; - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.heading = packet_in.heading; - packet1.heading_sp = packet_in.heading_sp; - packet1.altitude_amsl = packet_in.altitude_amsl; - packet1.altitude_sp = packet_in.altitude_sp; - packet1.wp_distance = packet_in.wp_distance; - packet1.base_mode = packet_in.base_mode; - packet1.landed_state = packet_in.landed_state; - packet1.throttle = packet_in.throttle; - packet1.airspeed = packet_in.airspeed; - packet1.airspeed_sp = packet_in.airspeed_sp; - packet1.groundspeed = packet_in.groundspeed; - packet1.climb_rate = packet_in.climb_rate; - packet1.gps_nsat = packet_in.gps_nsat; - packet1.gps_fix_type = packet_in.gps_fix_type; - packet1.battery_remaining = packet_in.battery_remaining; - packet1.temperature = packet_in.temperature; - packet1.temperature_air = packet_in.temperature_air; - packet1.failsafe = packet_in.failsafe; - packet1.wp_num = packet_in.wp_num; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_high_latency_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency_pack(system_id, component_id, &msg , packet1.base_mode , packet1.custom_mode , packet1.landed_state , packet1.roll , packet1.pitch , packet1.heading , packet1.throttle , packet1.heading_sp , packet1.latitude , packet1.longitude , packet1.altitude_amsl , packet1.altitude_sp , packet1.airspeed , packet1.airspeed_sp , packet1.groundspeed , packet1.climb_rate , packet1.gps_nsat , packet1.gps_fix_type , packet1.battery_remaining , packet1.temperature , packet1.temperature_air , packet1.failsafe , packet1.wp_num , packet1.wp_distance ); - mavlink_msg_high_latency_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.base_mode , packet1.custom_mode , packet1.landed_state , packet1.roll , packet1.pitch , packet1.heading , packet1.throttle , packet1.heading_sp , packet1.latitude , packet1.longitude , packet1.altitude_amsl , packet1.altitude_sp , packet1.airspeed , packet1.airspeed_sp , packet1.groundspeed , packet1.climb_rate , packet1.gps_nsat , packet1.gps_fix_type , packet1.battery_remaining , packet1.temperature , packet1.temperature_air , packet1.failsafe , packet1.wp_num , packet1.wp_distance ); - mavlink_msg_high_latency_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VIBRATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vibration_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,963498504,963498712,963498920 - }; - mavlink_vibration_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.vibration_x = packet_in.vibration_x; - packet1.vibration_y = packet_in.vibration_y; - packet1.vibration_z = packet_in.vibration_z; - packet1.clipping_0 = packet_in.clipping_0; - packet1.clipping_1 = packet_in.clipping_1; - packet1.clipping_2 = packet_in.clipping_2; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VIBRATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VIBRATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vibration_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vibration_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vibration_pack(system_id, component_id, &msg , packet1.time_usec , packet1.vibration_x , packet1.vibration_y , packet1.vibration_z , packet1.clipping_0 , packet1.clipping_1 , packet1.clipping_2 ); - mavlink_msg_vibration_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vibration_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.vibration_x , packet1.vibration_y , packet1.vibration_z , packet1.clipping_0 , packet1.clipping_1 , packet1.clipping_2 ); - mavlink_msg_vibration_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HOME_POSITION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_home_position_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,{ 185.0, 186.0, 187.0, 188.0 },297.0,325.0,353.0 - }; - mavlink_home_position_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.approach_x = packet_in.approach_x; - packet1.approach_y = packet_in.approach_y; - packet1.approach_z = packet_in.approach_z; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_home_position_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_home_position_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z ); - mavlink_msg_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_home_position_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z ); - mavlink_msg_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_HOME_POSITION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_home_position_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,{ 185.0, 186.0, 187.0, 188.0 },297.0,325.0,353.0,161 - }; - mavlink_set_home_position_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.approach_x = packet_in.approach_x; - packet1.approach_y = packet_in.approach_y; - packet1.approach_z = packet_in.approach_z; - packet1.target_system = packet_in.target_system; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_home_position_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_home_position_pack(system_id, component_id, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z ); - mavlink_msg_set_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_home_position_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z ); - mavlink_msg_set_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MESSAGE_INTERVAL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_message_interval_t packet_in = { - 963497464,17443 - }; - mavlink_message_interval_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.interval_us = packet_in.interval_us; - packet1.message_id = packet_in.message_id; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_message_interval_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_message_interval_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_message_interval_pack(system_id, component_id, &msg , packet1.message_id , packet1.interval_us ); - mavlink_msg_message_interval_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_message_interval_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.message_id , packet1.interval_us ); - mavlink_msg_message_interval_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_EXTENDED_SYS_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_extended_sys_state_t packet_in = { - 5,72 - }; - mavlink_extended_sys_state_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.vtol_state = packet_in.vtol_state; - packet1.landed_state = packet_in.landed_state; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_extended_sys_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_extended_sys_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_extended_sys_state_pack(system_id, component_id, &msg , packet1.vtol_state , packet1.landed_state ); - mavlink_msg_extended_sys_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_extended_sys_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.vtol_state , packet1.landed_state ); - mavlink_msg_extended_sys_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ADSB_VEHICLE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_adsb_vehicle_t packet_in = { - 963497464,963497672,963497880,963498088,18067,18171,18275,18379,18483,211,"BCDEFGHI",113,180 - }; - mavlink_adsb_vehicle_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.ICAO_address = packet_in.ICAO_address; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.altitude = packet_in.altitude; - packet1.heading = packet_in.heading; - packet1.hor_velocity = packet_in.hor_velocity; - packet1.ver_velocity = packet_in.ver_velocity; - packet1.flags = packet_in.flags; - packet1.squawk = packet_in.squawk; - packet1.altitude_type = packet_in.altitude_type; - packet1.emitter_type = packet_in.emitter_type; - packet1.tslc = packet_in.tslc; - - mav_array_memcpy(packet1.callsign, packet_in.callsign, sizeof(char)*9); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_adsb_vehicle_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_adsb_vehicle_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_adsb_vehicle_pack(system_id, component_id, &msg , packet1.ICAO_address , packet1.lat , packet1.lon , packet1.altitude_type , packet1.altitude , packet1.heading , packet1.hor_velocity , packet1.ver_velocity , packet1.callsign , packet1.emitter_type , packet1.tslc , packet1.flags , packet1.squawk ); - mavlink_msg_adsb_vehicle_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_adsb_vehicle_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ICAO_address , packet1.lat , packet1.lon , packet1.altitude_type , packet1.altitude , packet1.heading , packet1.hor_velocity , packet1.ver_velocity , packet1.callsign , packet1.emitter_type , packet1.tslc , packet1.flags , packet1.squawk ); - mavlink_msg_adsb_vehicle_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COLLISION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_collision_t packet_in = { - 963497464,45.0,73.0,101.0,53,120,187 - }; - mavlink_collision_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.id = packet_in.id; - packet1.time_to_minimum_delta = packet_in.time_to_minimum_delta; - packet1.altitude_minimum_delta = packet_in.altitude_minimum_delta; - packet1.horizontal_minimum_delta = packet_in.horizontal_minimum_delta; - packet1.src = packet_in.src; - packet1.action = packet_in.action; - packet1.threat_level = packet_in.threat_level; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COLLISION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COLLISION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_collision_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_collision_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_collision_pack(system_id, component_id, &msg , packet1.src , packet1.id , packet1.action , packet1.threat_level , packet1.time_to_minimum_delta , packet1.altitude_minimum_delta , packet1.horizontal_minimum_delta ); - mavlink_msg_collision_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_collision_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.src , packet1.id , packet1.action , packet1.threat_level , packet1.time_to_minimum_delta , packet1.altitude_minimum_delta , packet1.horizontal_minimum_delta ); - mavlink_msg_collision_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_V2_EXTENSION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_v2_extension_t packet_in = { - 17235,139,206,17,{ 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76 } - }; - mavlink_v2_extension_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.message_type = packet_in.message_type; - packet1.target_network = packet_in.target_network; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.payload, packet_in.payload, sizeof(uint8_t)*249); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_v2_extension_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_v2_extension_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_v2_extension_pack(system_id, component_id, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.message_type , packet1.payload ); - mavlink_msg_v2_extension_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_v2_extension_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.message_type , packet1.payload ); - mavlink_msg_v2_extension_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MEMORY_VECT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_memory_vect_t packet_in = { - 17235,139,206,{ 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48 } - }; - mavlink_memory_vect_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.address = packet_in.address; - packet1.ver = packet_in.ver; - packet1.type = packet_in.type; - - mav_array_memcpy(packet1.value, packet_in.value, sizeof(int8_t)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_memory_vect_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_memory_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_memory_vect_pack(system_id, component_id, &msg , packet1.address , packet1.ver , packet1.type , packet1.value ); - mavlink_msg_memory_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_memory_vect_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.address , packet1.ver , packet1.type , packet1.value ); - mavlink_msg_memory_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEBUG_VECT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_debug_vect_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,"UVWXYZABC" - }; - mavlink_debug_vect_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_vect_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_debug_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_vect_pack(system_id, component_id, &msg , packet1.name , packet1.time_usec , packet1.x , packet1.y , packet1.z ); - mavlink_msg_debug_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_vect_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.name , packet1.time_usec , packet1.x , packet1.y , packet1.z ); - mavlink_msg_debug_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_NAMED_VALUE_FLOAT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_named_value_float_t packet_in = { - 963497464,45.0,"IJKLMNOPQ" - }; - mavlink_named_value_float_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.value = packet_in.value; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_float_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_named_value_float_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_float_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_float_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_float_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_float_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_NAMED_VALUE_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_named_value_int_t packet_in = { - 963497464,963497672,"IJKLMNOPQ" - }; - mavlink_named_value_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.value = packet_in.value; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_named_value_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_STATUSTEXT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_statustext_t packet_in = { - 5,"BCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWX" - }; - mavlink_statustext_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.severity = packet_in.severity; - - mav_array_memcpy(packet1.text, packet_in.text, sizeof(char)*50); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_statustext_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_statustext_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_statustext_pack(system_id, component_id, &msg , packet1.severity , packet1.text ); - mavlink_msg_statustext_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_statustext_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.severity , packet1.text ); - mavlink_msg_statustext_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEBUG >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_debug_t packet_in = { - 963497464,45.0,29 - }; - mavlink_debug_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.value = packet_in.value; - packet1.ind = packet_in.ind; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DEBUG_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEBUG_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_debug_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.ind , packet1.value ); - mavlink_msg_debug_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.ind , packet1.value ); - mavlink_msg_debug_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 - -#ifndef M_PI_2 - #define M_PI_2 ((float)asin(1)) -#endif - -/** - * @file mavlink_conversions.h - * - * These conversion functions follow the NASA rotation standards definition file - * available online. - * - * Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free - * (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free) - * rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the - * protocol as widely as possible. - * - * @author James Goppert - * @author Thomas Gubler - */ - - -/** - * Converts a quaternion to a rotation matrix - * - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - * @param dcm a 3x3 rotation matrix - */ -MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3]) -{ - double a = quaternion[0]; - double b = quaternion[1]; - double c = quaternion[2]; - double d = quaternion[3]; - double aSq = a * a; - double bSq = b * b; - double cSq = c * c; - double dSq = d * d; - dcm[0][0] = aSq + bSq - cSq - dSq; - dcm[0][1] = 2 * (b * c - a * d); - dcm[0][2] = 2 * (a * c + b * d); - dcm[1][0] = 2 * (b * c + a * d); - dcm[1][1] = aSq - bSq + cSq - dSq; - dcm[1][2] = 2 * (c * d - a * b); - dcm[2][0] = 2 * (b * d - a * c); - dcm[2][1] = 2 * (a * b + c * d); - dcm[2][2] = aSq - bSq - cSq + dSq; -} - - -/** - * Converts a rotation matrix to euler angles - * - * @param dcm a 3x3 rotation matrix - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - */ -MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw) -{ - float phi, theta, psi; - theta = asin(-dcm[2][0]); - - if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) { - phi = 0.0f; - psi = (atan2f(dcm[1][2] - dcm[0][1], - dcm[0][2] + dcm[1][1]) + phi); - - } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) { - phi = 0.0f; - psi = atan2f(dcm[1][2] - dcm[0][1], - dcm[0][2] + dcm[1][1] - phi); - - } else { - phi = atan2f(dcm[2][1], dcm[2][2]); - psi = atan2f(dcm[1][0], dcm[0][0]); - } - - *roll = phi; - *pitch = theta; - *yaw = psi; -} - - -/** - * Converts a quaternion to euler angles - * - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - */ -MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw) -{ - float dcm[3][3]; - mavlink_quaternion_to_dcm(quaternion, dcm); - mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw); -} - - -/** - * Converts euler angles to a quaternion - * - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - */ -MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4]) -{ - float cosPhi_2 = cosf(roll / 2); - float sinPhi_2 = sinf(roll / 2); - float cosTheta_2 = cosf(pitch / 2); - float sinTheta_2 = sinf(pitch / 2); - float cosPsi_2 = cosf(yaw / 2); - float sinPsi_2 = sinf(yaw / 2); - quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 + - sinPhi_2 * sinTheta_2 * sinPsi_2); - quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 - - cosPhi_2 * sinTheta_2 * sinPsi_2); - quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 + - sinPhi_2 * cosTheta_2 * sinPsi_2); - quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 - - sinPhi_2 * sinTheta_2 * cosPsi_2); -} - - -/** - * Converts a rotation matrix to a quaternion - * Reference: - * - Shoemake, Quaternions, - * http://www.cs.ucr.edu/~vbz/resources/quatut.pdf - * - * @param dcm a 3x3 rotation matrix - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - */ -MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4]) -{ - float tr = dcm[0][0] + dcm[1][1] + dcm[2][2]; - if (tr > 0.0f) { - float s = sqrtf(tr + 1.0f); - quaternion[0] = s * 0.5f; - s = 0.5f / s; - quaternion[1] = (dcm[2][1] - dcm[1][2]) * s; - quaternion[2] = (dcm[0][2] - dcm[2][0]) * s; - quaternion[3] = (dcm[1][0] - dcm[0][1]) * s; - } else { - /* Find maximum diagonal element in dcm - * store index in dcm_i */ - int dcm_i = 0; - int i; - for (i = 1; i < 3; i++) { - if (dcm[i][i] > dcm[dcm_i][dcm_i]) { - dcm_i = i; - } - } - - int dcm_j = (dcm_i + 1) % 3; - int dcm_k = (dcm_i + 2) % 3; - - float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] - - dcm[dcm_k][dcm_k]) + 1.0f); - quaternion[dcm_i + 1] = s * 0.5f; - s = 0.5f / s; - quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s; - quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s; - quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s; - } -} - - -/** - * Converts euler angles to a rotation matrix - * - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - * @param dcm a 3x3 rotation matrix - */ -MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3]) -{ - float cosPhi = cosf(roll); - float sinPhi = sinf(roll); - float cosThe = cosf(pitch); - float sinThe = sinf(pitch); - float cosPsi = cosf(yaw); - float sinPsi = sinf(yaw); - - dcm[0][0] = cosThe * cosPsi; - dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi; - dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi; - - dcm[1][0] = cosThe * sinPsi; - dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi; - dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi; - - dcm[2][0] = -sinThe; - dcm[2][1] = sinPhi * cosThe; - dcm[2][2] = cosPhi * cosThe; -} - -#endif diff --git a/include/mavlink/v1.0/mavlink_helpers.h b/include/mavlink/v1.0/mavlink_helpers.h deleted file mode 100644 index 2587cdf..0000000 --- a/include/mavlink/v1.0/mavlink_helpers.h +++ /dev/null @@ -1,678 +0,0 @@ -#ifndef _MAVLINK_HELPERS_H_ -#define _MAVLINK_HELPERS_H_ - -#include "string.h" -#include "checksum.h" -#include "mavlink_types.h" -#include "mavlink_conversions.h" - -#ifndef MAVLINK_HELPER -#define MAVLINK_HELPER -#endif - -/* - * Internal function to give access to the channel status for each channel - */ -#ifndef MAVLINK_GET_CHANNEL_STATUS -MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) -{ -#ifdef MAVLINK_EXTERNAL_RX_STATUS - // No m_mavlink_status array defined in function, - // has to be defined externally -#else - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; -#endif - return &m_mavlink_status[chan]; -} -#endif - -/* - * Internal function to give access to the channel buffer for each channel - */ -#ifndef MAVLINK_GET_CHANNEL_BUFFER -MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) -{ - -#ifdef MAVLINK_EXTERNAL_RX_BUFFER - // No m_mavlink_buffer array defined in function, - // has to be defined externally -#else - static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; -#endif - return &m_mavlink_buffer[chan]; -} -#endif - -/** - * @brief Reset the status of a channel. - */ -MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan) -{ - mavlink_status_t *status = mavlink_get_channel_status(chan); - status->parse_state = MAVLINK_PARSE_STATE_IDLE; -} - -/** - * @brief Finalize a MAVLink message with channel assignment - * - * This function calculates the checksum and sets length and aircraft id correctly. - * It assumes that the message id and the payload are already correctly set. This function - * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack - * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. - * - * @param msg Message to finalize - * @param system_id Id of the sending (this) system, 1-127 - * @param length Message length - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra) -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length) -#endif -{ - // This is only used for the v2 protocol and we silence it here - (void)min_length; - // This code part is the same for all messages; - msg->magic = MAVLINK_STX; - msg->len = length; - msg->sysid = system_id; - msg->compid = component_id; - // One sequence number per channel - msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; - mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; - msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN); - crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len); -#if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &msg->checksum); -#endif - mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF); - mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8); - - return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; -} - - -/** - * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t min_length, uint8_t length, uint8_t crc_extra) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, min_length, length, crc_extra); -} -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); -} -#endif - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); - -/** - * @brief Finalize a MAVLink message with channel assignment and send - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, - uint8_t min_length, uint8_t length, uint8_t crc_extra) -#else -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) -#endif -{ - uint16_t checksum; - uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; - uint8_t ck[2]; - mavlink_status_t *status = mavlink_get_channel_status(chan); - buf[0] = MAVLINK_STX; - buf[1] = length; - buf[2] = status->current_tx_seq; - buf[3] = mavlink_system.sysid; - buf[4] = mavlink_system.compid; - buf[5] = msgid; - status->current_tx_seq++; - checksum = crc_calculate((const uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); - crc_accumulate_buffer(&checksum, packet, length); -#if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &checksum); -#endif - ck[0] = (uint8_t)(checksum & 0xFF); - ck[1] = (uint8_t)(checksum >> 8); - - MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); - _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); - _mavlink_send_uart(chan, packet, length); - _mavlink_send_uart(chan, (const char *)ck, 2); - MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); -} - -/** - * @brief re-send a message over a uart channel - * this is more stack efficient than re-marshalling the message - */ -MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg) -{ - uint8_t ck[2]; - - ck[0] = (uint8_t)(msg->checksum & 0xFF); - ck[1] = (uint8_t)(msg->checksum >> 8); - // XXX use the right sequence here - - MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); - _mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES); - _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len); - _mavlink_send_uart(chan, (const char *)ck, 2); - MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -/** - * @brief Pack a message to send it over a serial byte stream - */ -MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) -{ - memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); - - uint8_t *ck = buffer + (MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); - - ck[0] = (uint8_t)(msg->checksum & 0xFF); - ck[1] = (uint8_t)(msg->checksum >> 8); - - return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; -} - -union __mavlink_bitfield { - uint8_t uint8; - int8_t int8; - uint16_t uint16; - int16_t int16; - uint32_t uint32; - int32_t int32; -}; - - -MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) -{ - crc_init(&msg->checksum); -} - -MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) -{ - crc_accumulate(c, &msg->checksum); -} - -/** - * This is a varient of mavlink_frame_char() but with caller supplied - * parsing buffers. It is useful when you want to create a MAVLink - * parser in a library that doesn't use any global variables - * - * @param rxmsg parsing message buffer - * @param status parsing starus buffer - * @param c The char to parse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @param returnStats if a message was decoded, this is filled with the channel's stats - * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC - * - * A typical use scenario of this function call is: - * - * @code - * #include - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, - mavlink_status_t* status, - uint8_t c, - mavlink_message_t* r_message, - mavlink_status_t* r_mavlink_status) -{ - /* - default message crc function. You can override this per-system to - put this data in a different memory segment - */ -#if MAVLINK_CRC_EXTRA -#ifndef MAVLINK_MESSAGE_CRC - static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; -#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] -#endif -#endif - - /* Enable this option to check the length of each message. - This allows invalid messages to be caught much sooner. Use if the transmission - medium is prone to missing (or extra) characters (e.g. a radio that fades in - and out). Only use if the channel will only contain messages types listed in - the headers. - */ -#ifdef MAVLINK_CHECK_MESSAGE_LENGTH -#ifndef MAVLINK_MESSAGE_LENGTH - static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS; -#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid] -#endif -#endif - - int bufferIndex = 0; - - status->msg_received = MAVLINK_FRAMING_INCOMPLETE; - - switch (status->parse_state) - { - case MAVLINK_PARSE_STATE_UNINIT: - case MAVLINK_PARSE_STATE_IDLE: - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - rxmsg->magic = c; - mavlink_start_checksum(rxmsg); - } - break; - - case MAVLINK_PARSE_STATE_GOT_STX: - if (status->msg_received -/* Support shorter buffers than the - default maximum packet size */ -#if (MAVLINK_MAX_PAYLOAD_LEN < 255) - || c > MAVLINK_MAX_PAYLOAD_LEN -#endif - ) - { - status->buffer_overrun++; - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - } - else - { - // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 - rxmsg->len = c; - status->packet_idx = 0; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; - } - break; - - case MAVLINK_PARSE_STATE_GOT_LENGTH: - rxmsg->seq = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; - break; - - case MAVLINK_PARSE_STATE_GOT_SEQ: - rxmsg->sysid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; - break; - - case MAVLINK_PARSE_STATE_GOT_SYSID: - rxmsg->compid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; - break; - - case MAVLINK_PARSE_STATE_GOT_COMPID: -#ifdef MAVLINK_CHECK_MESSAGE_LENGTH - if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c)) - { - status->parse_error++; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - break; - } -#endif - rxmsg->msgid = c; - mavlink_update_checksum(rxmsg, c); - if (rxmsg->len == 0) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; - } - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID: - _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; - mavlink_update_checksum(rxmsg, c); - if (status->packet_idx == rxmsg->len) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - break; - - case MAVLINK_PARSE_STATE_GOT_PAYLOAD: -#if MAVLINK_CRC_EXTRA - mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); -#endif - if (c != (rxmsg->checksum & 0xFF)) { - status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1; - } else { - status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; - } - _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c; - break; - - case MAVLINK_PARSE_STATE_GOT_CRC1: - case MAVLINK_PARSE_STATE_GOT_BAD_CRC1: - if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) { - // got a bad CRC message - status->msg_received = MAVLINK_FRAMING_BAD_CRC; - } else { - // Successfully got message - status->msg_received = MAVLINK_FRAMING_OK; - } - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c; - memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); - break; - } - - bufferIndex++; - // If a message has been sucessfully decoded, check index - if (status->msg_received == MAVLINK_FRAMING_OK) - { - //while(status->current_seq != rxmsg->seq) - //{ - // status->packet_rx_drop_count++; - // status->current_seq++; - //} - status->current_rx_seq = rxmsg->seq; - // Initial condition: If no packet has been received so far, drop count is undefined - if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; - // Count this packet as received - status->packet_rx_success_count++; - } - - r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg - r_mavlink_status->parse_state = status->parse_state; - r_mavlink_status->packet_idx = status->packet_idx; - r_mavlink_status->current_rx_seq = status->current_rx_seq+1; - r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; - r_mavlink_status->packet_rx_drop_count = status->parse_error; - status->parse_error = 0; - - if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) { - /* - the CRC came out wrong. We now need to overwrite the - msg CRC with the one on the wire so that if the - caller decides to forward the message anyway that - mavlink_msg_to_send_buffer() won't overwrite the - checksum - */ - r_message->checksum = _MAV_PAYLOAD(rxmsg)[status->packet_idx] | (_MAV_PAYLOAD(rxmsg)[status->packet_idx+1]<<8); - } - - return status->msg_received; -} - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. This function will return 0, 1 or - * 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC) - * - * Messages are parsed into an internal buffer (one for each channel). When a complete - * message is received it is copies into *returnMsg and the channel's status is - * copied into *returnStats. - * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to parse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @param returnStats if a message was decoded, this is filled with the channel's stats - * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC - * - * A typical use scenario of this function call is: - * - * @code - * #include - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -{ - return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan), - mavlink_get_channel_status(chan), - c, - r_message, - r_mavlink_status); -} - - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. This function will return 0 or 1. - * - * Messages are parsed into an internal buffer (one for each channel). When a complete - * message is received it is copies into *returnMsg and the channel's status is - * copied into *returnStats. - * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to parse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @param returnStats if a message was decoded, this is filled with the channel's stats - * @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC - * - * A typical use scenario of this function call is: - * - * @code - * #include - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_parse_char(chan, byte, &msg)) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -{ - uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status); - if (msg_received == MAVLINK_FRAMING_BAD_CRC) { - // we got a bad CRC. Treat as a parse failure - mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); - mavlink_status_t* status = mavlink_get_channel_status(chan); - status->parse_error++; - status->msg_received = MAVLINK_FRAMING_INCOMPLETE; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - return 0; - } - return msg_received; -} - -/** - * @brief Put a bitfield of length 1-32 bit into the buffer - * - * @param b the value to add, will be encoded in the bitfield - * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. - * @param packet_index the position in the packet (the index of the first byte to use) - * @param bit_index the position in the byte (the index of the first bit to use) - * @param buffer packet buffer to write into - * @return new position of the last used byte in the buffer - */ -MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) -{ - uint16_t bits_remain = bits; - // Transform number into network order - int32_t v; - uint8_t i_bit_index, i_byte_index, curr_bits_n; -#if MAVLINK_NEED_BYTE_SWAP - union { - int32_t i; - uint8_t b[4]; - } bin, bout; - bin.i = b; - bout.b[0] = bin.b[3]; - bout.b[1] = bin.b[2]; - bout.b[2] = bin.b[1]; - bout.b[3] = bin.b[0]; - v = bout.i; -#else - v = b; -#endif - - // buffer in - // 01100000 01000000 00000000 11110001 - // buffer out - // 11110001 00000000 01000000 01100000 - - // Existing partly filled byte (four free slots) - // 0111xxxx - - // Mask n free bits - // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 - // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 - - // Shift n bits into the right position - // out = in >> n; - - // Mask and shift bytes - i_bit_index = bit_index; - i_byte_index = packet_index; - if (bit_index > 0) - { - // If bits were available at start, they were available - // in the byte before the current index - i_byte_index--; - } - - // While bits have not been packed yet - while (bits_remain > 0) - { - // Bits still have to be packed - // there can be more than 8 bits, so - // we might have to pack them into more than one byte - - // First pack everything we can into the current 'open' byte - //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 - //FIXME - if (bits_remain <= (uint8_t)(8 - i_bit_index)) - { - // Enough space - curr_bits_n = (uint8_t)bits_remain; - } - else - { - curr_bits_n = (8 - i_bit_index); - } - - // Pack these n bits into the current byte - // Mask out whatever was at that position with ones (xxx11111) - buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); - // Put content to this position, by masking out the non-used part - buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); - - // Increment the bit index - i_bit_index += curr_bits_n; - - // Now proceed to the next byte, if necessary - bits_remain -= curr_bits_n; - if (bits_remain > 0) - { - // Offer another 8 bits / one byte - i_byte_index++; - i_bit_index = 0; - } - } - - *r_bit_index = i_bit_index; - // If a partly filled byte is present, mark this as consumed - if (i_bit_index != 7) i_byte_index++; - return i_byte_index - packet_index; -} - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -// To make MAVLink work on your MCU, define comm_send_ch() if you wish -// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a -// whole packet at a time - -/* - -#include "mavlink_types.h" - -void comm_send_ch(mavlink_channel_t chan, uint8_t ch) -{ - if (chan == MAVLINK_COMM_0) - { - uart0_transmit(ch); - } - if (chan == MAVLINK_COMM_1) - { - uart1_transmit(ch); - } -} - */ - -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) -{ -#ifdef MAVLINK_SEND_UART_BYTES - /* this is the more efficient approach, if the platform - defines it */ - MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len); -#else - /* fallback to one byte at a time */ - uint16_t i; - for (i = 0; i < len; i++) { - comm_send_ch(chan, (uint8_t)buf[i]); - } -#endif -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -#endif /* _MAVLINK_HELPERS_H_ */ diff --git a/include/mavlink/v1.0/mavlink_types.h b/include/mavlink/v1.0/mavlink_types.h deleted file mode 100644 index 0a98ccc..0000000 --- a/include/mavlink/v1.0/mavlink_types.h +++ /dev/null @@ -1,228 +0,0 @@ -#ifndef MAVLINK_TYPES_H_ -#define MAVLINK_TYPES_H_ - -// Visual Studio versions before 2010 don't have stdint.h, so we just error out. -#if (defined _MSC_VER) && (_MSC_VER < 1600) -#error "The C-MAVLink implementation requires Visual Studio 2010 or greater" -#endif - -#include - -// Macro to define packed structures -#ifdef __GNUC__ - #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed)) -#else - #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) -#endif - -#ifndef MAVLINK_MAX_PAYLOAD_LEN -// it is possible to override this, but be careful! -#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length -#endif - -#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) -#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum -#define MAVLINK_NUM_CHECKSUM_BYTES 2 -#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) - -#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length - -#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 -#define MAVLINK_EXTENDED_HEADER_LEN 14 - -#if (defined _MSC_VER) || ((defined __APPLE__) && (defined __MACH__)) || (defined __linux__) - /* full fledged 32bit++ OS */ - #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 -#else - /* small microcontrollers */ - #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 -#endif - -#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) - - -/** - * Old-style 4 byte param union - * - * This struct is the data format to be used when sending - * parameters. The parameter should be copied to the native - * type (without type conversion) - * and re-instanted on the receiving side using the - * native type as well. - */ -MAVPACKED( -typedef struct param_union { - union { - float param_float; - int32_t param_int32; - uint32_t param_uint32; - 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; - - -/** - * New-style 8 byte param union - * mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering. - * The mavlink_param_union_double_t will be treated as a little-endian structure. - * - * If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero. - * The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the - * lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union. - * The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above, - * as bitfield ordering isn’t consistent between platforms. The above is intended to be for gcc on x86, - * which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number, - * and the bits pulled out using the shifts/masks. -*/ -MAVPACKED( -typedef struct param_union_extended { - union { - struct { - uint8_t is_double:1; - uint8_t mavlink_type:7; - union { - char c; - uint8_t uint8; - int8_t int8; - uint16_t uint16; - int16_t int16; - uint32_t uint32; - int32_t int32; - float f; - uint8_t align[7]; - }; - }; - uint8_t data[8]; - }; -}) mavlink_param_union_double_t; - -/** - * This structure is required to make the mavlink_send_xxx convenience functions - * work, as it tells the library what the current system and component ID are. - */ -MAVPACKED( -typedef struct __mavlink_system { - uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function -}) mavlink_system_t; - -MAVPACKED( -typedef struct __mavlink_message { - uint16_t checksum; ///< sent at end of packet - uint8_t magic; ///< protocol magic marker - uint8_t len; ///< Length of payload - uint8_t seq; ///< Sequence of packet - uint8_t sysid; ///< ID of message sender system/aircraft - uint8_t compid; ///< ID of the message sender component - uint8_t msgid; ///< ID of message in payload - uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; -}) mavlink_message_t; - -MAVPACKED( -typedef struct __mavlink_extended_message { - mavlink_message_t base_msg; - int32_t extended_payload_len; ///< Length of extended payload if any - uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; -}) mavlink_extended_message_t; - -typedef enum { - MAVLINK_TYPE_CHAR = 0, - MAVLINK_TYPE_UINT8_T = 1, - MAVLINK_TYPE_INT8_T = 2, - MAVLINK_TYPE_UINT16_T = 3, - MAVLINK_TYPE_INT16_T = 4, - MAVLINK_TYPE_UINT32_T = 5, - MAVLINK_TYPE_INT32_T = 6, - MAVLINK_TYPE_UINT64_T = 7, - MAVLINK_TYPE_INT64_T = 8, - MAVLINK_TYPE_FLOAT = 9, - MAVLINK_TYPE_DOUBLE = 10 -} mavlink_message_type_t; - -#define MAVLINK_MAX_FIELDS 64 - -typedef struct __mavlink_field_info { - const char *name; // name of this field - const char *print_format; // printing format hint, or NULL - mavlink_message_type_t type; // type of this field - unsigned int array_length; // if non-zero, field is an array - unsigned int wire_offset; // offset of each field in the payload - unsigned int structure_offset; // offset in a C structure -} mavlink_field_info_t; - -// note that in this structure the order of fields is the order -// in the XML file, not necessary the wire order -typedef struct __mavlink_message_info { - const char *name; // name of the message - unsigned num_fields; // how many fields in this message - mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information -} mavlink_message_info_t; - -#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) -#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) - -// checksum is immediately after the payload bytes -#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) -#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) - -typedef enum { - MAVLINK_COMM_0, - MAVLINK_COMM_1, - MAVLINK_COMM_2, - MAVLINK_COMM_3 -} mavlink_channel_t; - -/* - * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number - * of buffers they will use. If more are used, then the result will be - * a stack overrun - */ -#ifndef MAVLINK_COMM_NUM_BUFFERS -#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) -# define MAVLINK_COMM_NUM_BUFFERS 16 -#else -# define MAVLINK_COMM_NUM_BUFFERS 4 -#endif -#endif - -typedef enum { - MAVLINK_PARSE_STATE_UNINIT=0, - MAVLINK_PARSE_STATE_IDLE, - MAVLINK_PARSE_STATE_GOT_STX, - MAVLINK_PARSE_STATE_GOT_SEQ, - MAVLINK_PARSE_STATE_GOT_LENGTH, - MAVLINK_PARSE_STATE_GOT_SYSID, - MAVLINK_PARSE_STATE_GOT_COMPID, - MAVLINK_PARSE_STATE_GOT_MSGID, - MAVLINK_PARSE_STATE_GOT_PAYLOAD, - MAVLINK_PARSE_STATE_GOT_CRC1, - MAVLINK_PARSE_STATE_GOT_BAD_CRC1 -} mavlink_parse_state_t; ///< The state machine for the comm parser - -typedef enum { - MAVLINK_FRAMING_INCOMPLETE=0, - MAVLINK_FRAMING_OK=1, - MAVLINK_FRAMING_BAD_CRC=2 -} mavlink_framing_t; - -typedef struct __mavlink_status { - uint8_t msg_received; ///< Number of received messages - uint8_t buffer_overrun; ///< Number of buffer overruns - uint8_t parse_error; ///< Number of parse errors - mavlink_parse_state_t parse_state; ///< Parsing state machine - uint8_t packet_idx; ///< Index in current packet - uint8_t current_rx_seq; ///< Sequence number of last packet received - uint8_t current_tx_seq; ///< Sequence number of last packet sent - uint16_t packet_rx_success_count; ///< Received packets - uint16_t packet_rx_drop_count; ///< Number of packet drops -} mavlink_status_t; - -#define MAVLINK_BIG_ENDIAN 0 -#define MAVLINK_LITTLE_ENDIAN 1 - -#endif /* MAVLINK_TYPES_H_ */ diff --git a/include/mavlink/v1.0/message_definitions/common.xml b/include/mavlink/v1.0/message_definitions/common.xml deleted file mode 100644 index 2b69955..0000000 --- a/include/mavlink/v1.0/message_definitions/common.xml +++ /dev/null @@ -1,4087 +0,0 @@ - - - 3 - 0 - - - Micro air vehicle / autopilot classes. This identifies the individual model. - - Generic autopilot, full support for everything - - - Reserved for future use. - - - SLUGS autopilot, http://slugsuav.soe.ucsc.edu - - - ArduPilotMega / ArduCopter, http://diydrones.com - - - OpenPilot, http://openpilot.org - - - Generic autopilot only supporting simple waypoints - - - Generic autopilot supporting waypoints and other simple navigation commands - - - Generic autopilot supporting the full mission command set - - - No valid autopilot, e.g. a GCS or other MAVLink component - - - PPZ UAV - http://nongnu.org/paparazzi - - - UAV Dev Board - - - FlexiPilot - - - PX4 Autopilot - http://pixhawk.ethz.ch/px4/ - - - SMACCMPilot - http://smaccmpilot.org - - - AutoQuad -- http://autoquad.org - - - Armazila -- http://armazila.com - - - Aerob -- http://aerob.ru - - - ASLUAV autopilot -- http://www.asl.ethz.ch - - - SmartAP Autopilot - http://sky-drones.com - - - - - Generic micro air vehicle. - - - Fixed wing aircraft. - - - Quadrotor - - - Coaxial helicopter - - - Normal helicopter with tail rotor. - - - Ground installation - - - Operator control unit / ground control station - - - Airship, controlled - - - Free balloon, uncontrolled - - - Rocket - - - Ground rover - - - Surface vessel, boat, ship - - - Submarine - - - Hexarotor - - - Octorotor - - - Tricopter - - - Flapping wing - - - Kite - - - Onboard companion controller - - - Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. - - - Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. - - - Tiltrotor VTOL - - - - VTOL reserved 2 - - - VTOL reserved 3 - - - VTOL reserved 4 - - - VTOL reserved 5 - - - Onboard gimbal - - - Onboard ADSB peripheral - - - - These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. - - development release - - - alpha release - - - beta release - - - release candidate - - - official stable release - - - - - These flags encode the MAV mode. - - 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state. - - - 0b01000000 remote control input is enabled. - - - 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. - - - 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. - - - 0b00001000 guided mode enabled, system flies MISSIONs / mission items. - - - 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. - - - 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. - - - 0b00000001 Reserved for future use. - - - - These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. - - First bit: 10000000 - - - Second bit: 01000000 - - - Third bit: 00100000 - - - Fourth bit: 00010000 - - - Fifth bit: 00001000 - - - Sixt bit: 00000100 - - - Seventh bit: 00000010 - - - Eighth bit: 00000001 - - - - Override command, pauses current mission execution and moves immediately to a position - - Hold at the current position. - - - Continue with the next item in mission execution. - - - Hold at the current position of the system - - - Hold at the position specified in the parameters of the DO_HOLD action - - - - These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it - simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. - - System is not ready to fly, booting, calibrating, etc. No flag is set. - - - System is allowed to be active, under assisted RC control. - - - System is allowed to be active, under assisted RC control. - - - System is allowed to be active, under manual (RC) control, no stabilization - - - System is allowed to be active, under manual (RC) control, no stabilization - - - System is allowed to be active, under autonomous control, manual setpoint - - - System is allowed to be active, under autonomous control, manual setpoint - - - System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) - - - System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) - - - UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. - - - UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. - - - - - Uninitialized system, state is unknown. - - - System is booting up. - - - System is calibrating and not flight-ready. - - - System is grounded and on standby. It can be launched any time. - - - System is active and might be already airborne. Motors are engaged. - - - System is in a non-normal flight mode. It can however still navigate. - - - System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. - - - System just initialized its power-down sequence, will shut down now. - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - On Screen Display (OSD) devices for video links - - - Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - These encode the sensors whose status is sent as part of the SYS_STATUS message. - - 0x01 3D gyro - - - 0x02 3D accelerometer - - - 0x04 3D magnetometer - - - 0x08 absolute pressure - - - 0x10 differential pressure - - - 0x20 GPS - - - 0x40 optical flow - - - 0x80 computer vision position - - - 0x100 laser based position - - - 0x200 external ground truth (Vicon or Leica) - - - 0x400 3D angular rate control - - - 0x800 attitude stabilization - - - 0x1000 yaw position - - - 0x2000 z/altitude control - - - 0x4000 x/y position control - - - 0x8000 motor outputs / control - - - 0x10000 rc receiver - - - 0x20000 2nd 3D gyro - - - 0x40000 2nd 3D accelerometer - - - 0x80000 2nd 3D magnetometer - - - 0x100000 geofence - - - 0x200000 AHRS subsystem health - - - 0x400000 Terrain subsystem health - - - 0x800000 Motors are reversed - - - 0x1000000 Logging - - - 0x2000000 Battery - - - - - Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) - - - Local coordinate frame, Z-up (x: north, y: east, z: down). - - - NOT a coordinate frame, indicates a mission command. - - - Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. - - - Local coordinate frame, Z-down (x: east, y: north, z: up) - - - Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) - - - Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. - - - Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. - - - Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. - - - Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. - - - Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. - - - Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. - - - - - - - - - - - - - - - - - - - - - - - - - - Disable fenced mode - - - Switched to guided mode to return point (fence point 0) - - - Report fence breach, but don't take action - - - Switched to guided mode to return point (fence point 0) with manual throttle control - - - Switch to RTL (return to launch) mode and head for the return point. - - - - - No last fence breach - - - Breached minimum altitude - - - Breached maximum altitude - - - Breached fence boundary - - - - - Enumeration of possible mount operation modes - - Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization - - - Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. - - - Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization - - - Load neutral position and start RC Roll,Pitch,Yaw control with stabilization - - - Load neutral position and start to point to Lat,Lon,Alt - - - - Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. - - Navigate to MISSION. - Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) - Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached) - 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. - Desired yaw angle at MISSION (rotary wing). NaN for unchanged. - Latitude - Longitude - Altitude - - - 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 - - - Loiter around this MISSION for X turns - Turns - Empty - Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise - Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle - Latitude - Longitude - Altitude - - - Loiter around this MISSION for X seconds - Seconds (decimal) - Empty - Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise - Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle - Latitude - Longitude - Altitude - - - Return to launch location - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Land at location - Abort Alt - Empty - Empty - Desired yaw angle. NaN for unchanged. - Latitude - Longitude - Altitude - - - Takeoff from ground / hand - Minimum pitch (if airspeed sensor present), desired pitch without sensor - Empty - Empty - Yaw angle (if magnetometer present), ignored without magnetometer. NaN for unchanged. - Latitude - Longitude - Altitude - - - Land at local position (local frame only) - Landing target number (if available) - Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land - Landing descend rate [ms^-1] - Desired yaw angle [rad] - Y-axis position [m] - X-axis position [m] - Z-axis / ground level position [m] - - - Takeoff from local position (local frame only) - Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad] - Empty - Takeoff ascend rate [ms^-1] - Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these - Y-axis position [m] - X-axis position [m] - Z-axis position [m] - - - Vehicle following, i.e. this waypoint represents the position of a moving vehicle - Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation - Ground speed of vehicle to be followed - Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise - Desired yaw angle. - Latitude - Longitude - Altitude - - - Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. - Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. - Empty - Empty - Empty - Empty - Empty - Desired altitude in meters - - - Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. - Heading Required (0 = False) - Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter. - Empty - Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location - Latitude - Longitude - Altitude - - - Being following a target - System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode - RESERVED - RESERVED - altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home - altitude - RESERVED - TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout - - - Reposition the MAV after a follow target command has been sent - Camera q1 (where 0 is on the ray from the camera to the tracking device) - Camera q2 - Camera q3 - Camera q4 - altitude offset from target (m) - X offset from target (m) - Y offset from target (m) - - - 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 - - - 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 - - - Navigate to MISSION using a spline path. - Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) - Empty - Empty - Empty - Latitude/X of goal - Longitude/Y of goal - Altitude/Z of goal - - - Takeoff from ground using VTOL mode - Empty - Empty - Empty - Yaw angle in degrees. NaN for unchanged. - Latitude - Longitude - Altitude - - - Land using VTOL mode - Empty - Empty - Empty - Yaw angle in degrees. NaN for unchanged. - Latitude - Longitude - Altitude - - - - hand control over to an external controller - On / Off (> 0.5f on) - Empty - Empty - Empty - Empty - Empty - Empty - - - Delay the next navigation command a number of seconds or until a specified time - Delay in seconds (decimal, -1 to enable time-of-day fields) - hour (24h format, UTC, -1 to ignore) - minute (24h format, UTC, -1 to ignore) - second (24h format, UTC) - Empty - Empty - Empty - - - Descend and place payload. Vehicle descends until it detects a hanging payload has reached the ground, the gripper is opened to release the payload - Maximum distance to descend (meters) - Empty - Empty - Empty - Latitude (deg * 1E7) - Longitude (deg * 1E7) - Altitude (meters) - - - NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Delay mission state machine. - Delay in seconds (decimal) - Empty - Empty - Empty - Empty - Empty - Empty - - - Ascend/descend at rate. Delay mission state machine until desired altitude reached. - Descent / Ascend rate (m/s) - Empty - Empty - Empty - Empty - Empty - Finish Altitude - - - Delay mission state machine until within desired distance of next NAV point. - Distance (meters) - Empty - Empty - Empty - Empty - Empty - Empty - - - Reach a certain target angle. - target angle: [0-360], 0 is north - speed during yaw change:[deg per second] - direction: negative: counter clockwise, positive: clockwise [-1,1] - relative offset or absolute angle: [ 1,0] - Empty - Empty - Empty - - - NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Set system mode. - Mode, as defined by ENUM MAV_MODE - Custom mode - this is system specific, please refer to the individual autopilot specifications for details. - Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details. - Empty - Empty - Empty - Empty - - - Jump to the desired command in the mission list. Repeat this action only the specified number of times - Sequence number - Repeat count - Empty - Empty - Empty - Empty - Empty - - - Change speed and/or throttle set points. - Speed type (0=Airspeed, 1=Ground Speed) - Speed (m/s, -1 indicates no change) - Throttle ( Percent, -1 indicates no change) - absolute or relative [0,1] - Empty - Empty - Empty - - - Changes the home location either to the current location or a specified location. - Use current (1=use current location, 0=use specified location) - Empty - Empty - Empty - Latitude - Longitude - Altitude - - - Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. - Parameter number - Parameter value - Empty - Empty - Empty - Empty - Empty - - - Set a relay to a condition. - Relay number - Setting (1=on, 0=off, others possible depending on system hardware) - Empty - Empty - Empty - Empty - Empty - - - Cycle a relay on and off for a desired number of cyles with a desired period. - Relay number - Cycle count - Cycle time (seconds, decimal) - Empty - Empty - Empty - Empty - - - Set a servo to a desired PWM value. - Servo number - PWM (microseconds, 1000 to 2000 typical) - Empty - Empty - Empty - Empty - Empty - - - Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. - Servo number - PWM (microseconds, 1000 to 2000 typical) - Cycle count - Cycle time (seconds) - Empty - Empty - Empty - - - Terminate flight immediately - Flight termination activated if > 0.5 - Empty - Empty - Empty - Empty - Empty - Empty - - - Change altitude set point. - Altitude in meters - Mav frame of new altitude (see MAV_FRAME) - Empty - Empty - Empty - Empty - Empty - - - Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0 if not needed. If specified then it will be used to help find the closest landing sequence. - Empty - Empty - Empty - Empty - Latitude - Longitude - Empty - - - Mission command to perform a landing from a rally point. - Break altitude (meters) - Landing speed (m/s) - Empty - Empty - Empty - Empty - Empty - - - Mission command to safely abort an autonmous landing. - Altitude (meters) - Empty - Empty - Empty - Empty - Empty - Empty - - - Reposition the vehicle to a specific WGS84 global position. - Ground speed, less than 0 (-1) for default - Bitmask of option flags, see the MAV_DO_REPOSITION_FLAGS enum. - Reserved - Yaw heading, NaN for unchanged. For planes indicates loiter direction (0: clockwise, 1: counter clockwise) - Latitude (deg * 1E7) - Longitude (deg * 1E7) - Altitude (meters) - - - If in a GPS controlled position mode, hold the current position or continue. - 0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - Set moving direction to forward or reverse. - Direction (0=Forward, 1=Reverse) - Empty - Empty - Empty - Empty - Empty - Empty - - - Control onboard camera system. - Camera ID (-1 for all) - Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw - Transmission mode: 0: video stream, >0: single images every n seconds (decimal) - Recording: 0: disabled, 1: enabled compressed, 2: enabled raw - Empty - Empty - Empty - - - Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various 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 - - - - - Mission command to configure an on-board camera controller system. - Modes: P, TV, AV, M, Etc - Shutter speed: Divisor number for one second - Aperture: F stop number - ISO number e.g. 80, 100, 200, Etc - Exposure type enumerator - Command Identity - Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) - - - Mission command to control an on-board camera controller system. - Session control e.g. show/hide lens - Zoom's absolute position - Zooming step value to offset zoom from the current position - Focus Locking, Unlocking or Re-locking - Shooting Command - Command Identity - Test shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count. - - - - Mission command to configure a camera or antenna mount - Mount operation mode (see MAV_MOUNT_MODE enum) - stabilize roll? (1 = yes, 0 = no) - stabilize pitch? (1 = yes, 0 = no) - stabilize yaw? (1 = yes, 0 = no) - Empty - Empty - Empty - - - Mission command to control a camera or antenna mount - pitch (WIP: DEPRECATED: or lat in degrees) depending on mount mode. - roll (WIP: DEPRECATED: or lon in degrees) depending on mount mode. - yaw (WIP: DEPRECATED: or alt in meters) depending on mount mode. - WIP: alt in meters depending on mount mode. - WIP: latitude in degrees * 1E7, set if appropriate mount mode. - WIP: longitude in degrees * 1E7, set if appropriate mount mode. - MAV_MOUNT_MODE enum value - - - Mission command to set camera trigger distance for this flight. The camera is trigerred each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera. - Camera trigger distance (meters). -1 or 0 to ignore - Camera shutter integration time (milliseconds). -1 or 0 to ignore - Empty - Empty - Empty - Empty - Empty - - - Mission command to enable the geofence - enable? (0=disable, 1=enable, 2=disable_floor_only) - Empty - Empty - Empty - Empty - Empty - Empty - - - Mission command to trigger a parachute - action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.) - Empty - Empty - Empty - Empty - Empty - Empty - - - Mission command to perform motor test - motor sequence number (a number from 1 to max number of motors on the vehicle) - throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) - throttle - timeout (in seconds) - Empty - Empty - Empty - - - Change to/from inverted flight - inverted (0=normal, 1=inverted) - Empty - Empty - Empty - Empty - Empty - Empty - - - - Sets a desired vehicle turn angle and speed change - yaw angle to adjust steering by in centidegress - speed - normalized to 0 .. 1 - Empty - Empty - Empty - Empty - Empty - - - Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera. - Camera trigger cycle time (milliseconds). -1 or 0 to ignore. - Camera shutter integration time (milliseconds). Should be less than trigger cycle time. -1 or 0 to ignore. - Empty - Empty - Empty - Empty - Empty - - - Mission command to control a camera or antenna mount, using a quaternion as reference. - q1 - quaternion param #1, w (1 in null-rotation) - q2 - quaternion param #2, x (0 in null-rotation) - q3 - quaternion param #3, y (0 in null-rotation) - q4 - quaternion param #4, z (0 in null-rotation) - Empty - Empty - Empty - - - set id of master controller - System ID - Component ID - Empty - Empty - Empty - Empty - Empty - - - set limits for external control - timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout - absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit - absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit - horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit - Empty - Empty - Empty - - - Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines - 0: Stop engine, 1:Start Engine - 0: Warm start, 1:Cold start. Controls use of choke where applicable - Height delay (meters). This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay. - Empty - Empty - Empty - Empty - Empty - - - NOP - This command is only used to mark the upper limit of the DO commands in the enumeration - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero. - 1: gyro calibration, 3: gyro temperature calibration - 1: magnetometer calibration - 1: ground pressure calibration - 1: radio RC calibration, 2: RC trim calibration - 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration - 1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration - 1: ESC calibration, 3: barometer temperature calibration - - - Set sensor offsets. This command will be only accepted if in pre-flight mode. - Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometer - X axis offset (or generic dimension 1), in the sensor's raw units - Y axis offset (or generic dimension 2), in the sensor's raw units - Z axis offset (or generic dimension 3), in the sensor's raw units - Generic dimension 4, in the sensor's raw units - Generic dimension 5, in the sensor's raw units - Generic dimension 6, in the sensor's raw units - - - Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. - 1: Trigger actuator ID assignment and direction mapping. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. - Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults - Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults - Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging) - Reserved - Empty - Empty - Empty - - - Request the reboot or shutdown of system components. - 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded. - 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded. - WIP: 0: Do nothing for camera, 1: Reboot onboard camera, 2: Shutdown onboard camera, 3: Reboot onboard camera and keep it in the bootloader until upgraded - WIP: 0: Do nothing for mount (e.g. gimbal), 1: Reboot mount, 2: Shutdown mount, 3: Reboot mount and keep it in the bootloader until upgraded - Reserved, send 0 - Reserved, send 0 - WIP: ID (e.g. camera ID -1 for all IDs) - - - 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 - - - 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) - - - Arms / Disarms a component - 1 to arm, 0 to disarm - - - Request the home position from the vehicle. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - Starts receiver pairing - 0:Spektrum - 0:Spektrum DSM2, 1:Spektrum DSMX - - - Request the interval between messages for a particular MAVLink message ID - The MAVLink message ID - - - Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM - The MAVLink message ID - The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate. - - - Request autopilot capabilities - 1: Request autopilot version - Reserved (all remaining params) - - - WIP: Request camera information (CAMERA_INFORMATION) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - 0: No action 1: Request camera capabilities - Reserved (all remaining params) - - - WIP: Request camera settings (CAMERA_SETTINGS) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - 0: No Action 1: Request camera settings - Reserved (all remaining params) - - - WIP: Set the camera settings part 1 (CAMERA_SETTINGS). Use NAN for values you don't want to change. - Camera ID (1 for first, 2 for second, etc.) - Aperture (1/value) - Shutter speed in seconds - ISO sensitivity - AE mode (Auto Exposure) (0: full auto 1: full manual 2: aperture priority 3: shutter priority) - EV value (when in auto exposure) - White balance (color temperature in K) (0: Auto WB) - - - WIP: Set the camera settings part 2 (CAMERA_SETTINGS). Use NAN for values you don't want to change. - Camera ID (1 for first, 2 for second, etc.) - Camera mode (0: photo, 1: video) - Audio recording enabled (0: off 1: on) - Reserved for metering mode ID (Average, Center, Spot, etc.) - Reserved for image format ID (Jpeg/Raw/Jpeg+Raw) - Reserved for image quality ID (Compression) - Reserved for color mode ID (Neutral, Vivid, etc.) - - - WIP: Request storage information (STORAGE_INFORMATION) - Storage ID (0 for all, 1 for first, 2 for second, etc.) - 0: No Action 1: Request storage information - Reserved (all remaining params) - - - WIP: Format a storage medium - Storage ID (1 for first, 2 for second, etc.) - 0: No action 1: Format storage - Reserved (all remaining params) - - - WIP: Request camera capture status (CAMERA_CAPTURE_STATUS) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - 0: No Action 1: Request camera capture status - Reserved (all remaining params) - - - WIP: Request flight information (FLIGHT_INFORMATION) - 1: Request flight information - Reserved (all remaining params) - - - WIP: Reset all camera settings to Factory Default (CAMERA_SETTINGS) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - 0: No Action 1: Reset all settings - Reserved (all remaining params) - - - WIP: Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Duration between two consecutive pictures (in seconds) - Number of images to capture total - 0 for unlimited capture - Resolution horizontal in pixels (set to -1 for highest resolution possible) - Resolution vertical in pixels (set to -1 for highest resolution possible) - - - WIP: Stop image capture sequence - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Reserved - - - WIP: Re-request a CAMERA_IMAGE_CAPTURE packet - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Sequence number for missing CAMERA_IMAGE_CAPTURE packet - Reserved (all remaining params) - - - Enable or disable on-board camera triggering system. - Trigger enable/disable (0 for disable, 1 for start), -1 to ignore - 1 to reset the trigger sequence, -1 or 0 to ignore - 1 to pause triggering, but without switching the camera off or retracting it. -1 to ignore - - - WIP: Starts video capture (recording) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Frames per second, set to -1 for highest framerate possible. - Resolution horizontal in pixels (set to -1 for highest resolution possible) - Resolution vertical in pixels (set to -1 for highest resolution possible) - Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise time in Hz) - - - WIP: Stop the current video capture (recording) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Reserved - - - WIP: Start video streaming - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Reserved - - - WIP: Stop the current video streaming - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Reserved - - - WIP: Request video stream information (VIDEO_STREAM_INFORMATION) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - 0: No Action 1: Request video stream information - Reserved (all remaining params) - - - Request to start streaming logging data over MAVLink (see also LOGGING_DATA message) - Format: 0: ULog - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - - - Request to stop streaming log data over MAVLink - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - - - - Landing gear ID (default: 0, -1 for all) - Landing gear position (Down: 0, Up: 1, NAN for no change) - Reserved, set to NAN - Reserved, set to NAN - Reserved, set to NAN - Reserved, set to NAN - Reserved, set to NAN - - - Create a panorama at the current position - Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle) - Viewing angle vertical of panorama (in degrees) - Speed of the horizontal rotation (in degrees per second) - Speed of the vertical rotation (in degrees per second) - - - Request VTOL transition - The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used. - - - This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocites along all three axes. - - - - This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position. - - Radius of desired circle in CIRCLE_MODE - User defined - User defined - User defined - Unscaled target latitude of center of circle in CIRCLE_MODE - Unscaled target longitude of center of circle in CIRCLE_MODE - - - Fence return point. There can only be one fence return point. - - Reserved - Reserved - Reserved - Reserved - Latitude - Longitude - Altitude - - - Fence vertex for an inclusion polygon. The vehicle must stay within this area. Minimum of 3 vertices required. - - Polygon vertex count - Reserved - Reserved - Reserved - Latitude - Longitude - Reserved - - - Fence vertex for an exclusion polygon. The vehicle must stay outside this area. Minimum of 3 vertices required. - - Polygon vertex count - Reserved - Reserved - Reserved - Latitude - Longitude - Reserved - - - Rally point. You can have multiple rally points defined. - - Reserved - Reserved - Reserved - Reserved - Latitude - Longitude - Altitude - - - - - Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. - Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list. - Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will. - Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will. - Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will. - Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT - Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT - Altitude, in meters AMSL - - - Control the payload deployment. - Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - - - THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a - recommendation to the autopilot software. Individual autopilots may or may not obey - the recommended messages. - - Enable all data streams - - - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. - - - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS - - - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW - - - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. - - - Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. - - - Dependent on the autopilot - - - Dependent on the autopilot - - - Dependent on the autopilot - - - - The ROI (region of interest) for the vehicle. This can be - be used by the vehicle for camera/vehicle attitude alignment (see - MAV_CMD_NAV_ROI). - - No region of interest. - - - Point toward next MISSION. - - - Point toward given MISSION. - - - Point toward fixed location. - - - Point toward of given id. - - - - ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. - - Command / mission item is ok. - - - Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. - - - The system is refusing to accept this command from this source / communication partner. - - - Command or mission item is not supported, other commands would be accepted. - - - The coordinate frame of this command / mission item is not supported. - - - The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. - - - The X or latitude value is out of range. - - - The Y or longitude value is out of range. - - - The Z or altitude value is out of range. - - - - Specifies the datatype of a MAVLink parameter. - - 8-bit unsigned integer - - - 8-bit signed integer - - - 16-bit unsigned integer - - - 16-bit signed integer - - - 32-bit unsigned integer - - - 32-bit signed integer - - - 64-bit unsigned integer - - - 64-bit signed integer - - - 32-bit floating-point - - - 64-bit floating-point - - - - result from a mavlink command - - Command ACCEPTED and EXECUTED - - - Command TEMPORARY REJECTED/DENIED - - - Command PERMANENTLY DENIED - - - Command UNKNOWN/UNSUPPORTED - - - Command executed, but failed - - - WIP: Command being executed - - - - result in a mavlink mission ack - - mission accepted OK - - - generic error / not accepting mission commands at all right now - - - coordinate frame is not supported - - - command is not supported - - - mission item exceeds storage space - - - one of the parameters has an invalid value - - - param1 has an invalid value - - - param2 has an invalid value - - - param3 has an invalid value - - - param4 has an invalid value - - - x/param5 has an invalid value - - - y/param6 has an invalid value - - - param7 has an invalid value - - - received waypoint out of sequence - - - not accepting any mission commands from this communication partner - - - - Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. - - System is unusable. This is a "panic" condition. - - - Action should be taken immediately. Indicates error in non-critical systems. - - - Action must be taken immediately. Indicates failure in a primary system. - - - Indicates an error in secondary/redundant systems. - - - Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. - - - An unusual event has occured, though not an error condition. This should be investigated for the root cause. - - - Normal operational messages. Useful for logging. No action is required for these messages. - - - Useful non-operational messages that can assist in debugging. These should not occur during normal operation. - - - - Power supply status flags (bitmask) - - main brick power supply valid - - - main servo power supply valid for FMU - - - USB power is connected - - - peripheral supply is in over-current state - - - hi-power peripheral supply is in over-current state - - - Power status has changed since boot - - - - SERIAL_CONTROL device types - - First telemetry port - - - Second telemetry port - - - First GPS port - - - Second GPS port - - - system shell - - - - SERIAL_CONTROL flags (bitmask) - - Set if this is a reply - - - Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message - - - Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set - - - Block on writes to the serial port - - - Send multiple replies until port is drained - - - - Enumeration of distance sensor types - - Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units - - - Ultrasound rangefinder, e.g. MaxBotix units - - - Infrared rangefinder, e.g. Sharp units - - - - Enumeration of sensor orientation, according to its rotations - - Roll: 0, Pitch: 0, Yaw: 0 - - - Roll: 0, Pitch: 0, Yaw: 45 - - - Roll: 0, Pitch: 0, Yaw: 90 - - - Roll: 0, Pitch: 0, Yaw: 135 - - - Roll: 0, Pitch: 0, Yaw: 180 - - - Roll: 0, Pitch: 0, Yaw: 225 - - - Roll: 0, Pitch: 0, Yaw: 270 - - - Roll: 0, Pitch: 0, Yaw: 315 - - - Roll: 180, Pitch: 0, Yaw: 0 - - - Roll: 180, Pitch: 0, Yaw: 45 - - - Roll: 180, Pitch: 0, Yaw: 90 - - - Roll: 180, Pitch: 0, Yaw: 135 - - - Roll: 0, Pitch: 180, Yaw: 0 - - - Roll: 180, Pitch: 0, Yaw: 225 - - - Roll: 180, Pitch: 0, Yaw: 270 - - - Roll: 180, Pitch: 0, Yaw: 315 - - - Roll: 90, Pitch: 0, Yaw: 0 - - - Roll: 90, Pitch: 0, Yaw: 45 - - - Roll: 90, Pitch: 0, Yaw: 90 - - - Roll: 90, Pitch: 0, Yaw: 135 - - - Roll: 270, Pitch: 0, Yaw: 0 - - - Roll: 270, Pitch: 0, Yaw: 45 - - - Roll: 270, Pitch: 0, Yaw: 90 - - - Roll: 270, Pitch: 0, Yaw: 135 - - - Roll: 0, Pitch: 90, Yaw: 0 - - - Roll: 0, Pitch: 270, Yaw: 0 - - - Roll: 0, Pitch: 180, Yaw: 90 - - - Roll: 0, Pitch: 180, Yaw: 270 - - - Roll: 90, Pitch: 90, Yaw: 0 - - - Roll: 180, Pitch: 90, Yaw: 0 - - - Roll: 270, Pitch: 90, Yaw: 0 - - - Roll: 90, Pitch: 180, Yaw: 0 - - - Roll: 270, Pitch: 180, Yaw: 0 - - - Roll: 90, Pitch: 270, Yaw: 0 - - - Roll: 180, Pitch: 270, Yaw: 0 - - - Roll: 270, Pitch: 270, Yaw: 0 - - - Roll: 90, Pitch: 180, Yaw: 90 - - - Roll: 90, Pitch: 0, Yaw: 270 - - - Roll: 315, Pitch: 315, Yaw: 315 - - - - Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. - - Autopilot supports MISSION float message type. - - - Autopilot supports the new param float message type. - - - Autopilot supports MISSION_INT scaled integer message type. - - - Autopilot supports COMMAND_INT scaled integer message type. - - - Autopilot supports the new param union message type. - - - Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. - - - Autopilot supports commanding attitude offboard. - - - Autopilot supports commanding position and velocity targets in local NED frame. - - - Autopilot supports commanding position and velocity targets in global scaled integers. - - - Autopilot supports terrain protocol / data handling. - - - Autopilot supports direct actuator control. - - - Autopilot supports the flight termination command. - - - Autopilot supports onboard compass calibration. - - - Autopilot supports mavlink version 2. - - - Autopilot supports mission fence protocol. - - - Autopilot supports mission rally point protocol. - - - Autopilot supports the flight information protocol. - - - - Type of mission items being requested/sent in mission protocol. - - Items are mission commands for main mission. - - - Specifies GeoFence area(s). Items are MAV_CMD_FENCE_ GeoFence items. - - - Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_RALLY_POINT rally point items. - - - Only used in MISSION_CLEAR_ALL to clear all mission types. - - - - Enumeration of estimator types - - This is a naive estimator without any real covariance feedback. - - - Computer vision based estimate. Might be up to scale. - - - Visual-inertial estimate. - - - Plain GPS estimate. - - - Estimator integrating GPS and inertial sensing. - - - - Enumeration of battery types - - Not specified. - - - Lithium polymer battery - - - Lithium-iron-phosphate battery - - - Lithium-ION battery - - - Nickel metal hydride battery - - - - Enumeration of battery functions - - Battery function is unknown - - - Battery supports all flight systems - - - Battery for the propulsion system - - - Avionics battery - - - Payload battery - - - - Enumeration of VTOL states - - MAV is not configured as VTOL - - - VTOL is in transition from multicopter to fixed-wing - - - VTOL is in transition from fixed-wing to multicopter - - - VTOL is in multicopter state - - - VTOL is in fixed-wing state - - - - Enumeration of landed detector states - - MAV landed state is unknown - - - MAV is landed (on ground) - - - MAV is in air - - - MAV currently taking off - - - MAV currently landing - - - - Enumeration of the ADSB altimeter types - - Altitude reported from a Baro source using QNH reference - - - Altitude reported from a GNSS source - - - - ADSB classification for the type of vehicle emitting the transponder signal - - - - - - - - - - - - - - - - - - - - - - - These flags indicate status such as data validity of each data source. Set = data valid - - - - - - - - - - Bitmask of options for the MAV_CMD_DO_REPOSITION - - The aircraft should immediately transition into guided. This should not be set for follow me applications - - - - - Flags in EKF_STATUS message - - True if the attitude estimate is good - - - True if the horizontal velocity estimate is good - - - True if the vertical velocity estimate is good - - - True if the horizontal position (relative) estimate is good - - - True if the horizontal position (absolute) estimate is good - - - True if the vertical position (absolute) estimate is good - - - True if the vertical position (above ground) estimate is good - - - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) - - - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate - - - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate - - - True if the EKF has detected a GPS glitch - - - - - - throttle as a percentage from 0 ~ 100 - - - throttle as an absolute PWM value (normally in range of 1000~2000) - - - throttle pass-through from pilot's transmitter - - - - - - ignore altitude field - - - ignore hdop field - - - ignore vdop field - - - ignore horizontal velocity field (vn and ve) - - - ignore vertical velocity field (vd) - - - ignore speed accuracy field - - - ignore horizontal accuracy field - - - ignore vertical accuracy field - - - - Possible actions an aircraft can take to avoid a collision. - - Ignore any potential collisions - - - Report potential collision - - - Ascend or Descend to avoid threat - - - Move horizontally to avoid threat - - - Aircraft to move perpendicular to the collision's velocity vector - - - Aircraft to fly directly back to its launch point - - - Aircraft to stop in place - - - - Aircraft-rated danger from this threat. - - Not a threat - - - Craft is mildly concerned about this threat - - - Craft is panicing, and may take actions to avoid threat - - - - Source of information about this collision. - - ID field references ADSB_VEHICLE packets - - - ID field references MAVLink SRC ID - - - - Type of GPS fix - - No GPS connected - - - No position information, GPS is connected - - - 2D position - - - 3D position - - - DGPS/SBAS aided 3D position - - - RTK float, 3D position - - - RTK Fixed, 3D position - - - Static fixed, typically used for base stations - - - - - - The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). - Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - Autopilot type / class. defined in MAV_AUTOPILOT ENUM - System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - A bitfield for use for autopilot-specific flags. - System status flag, see MAV_STATE ENUM - MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version - - - The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. - Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - Battery voltage, in millivolts (1 = 1 millivolt) - Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - Autopilot-specific errors - Autopilot-specific errors - Autopilot-specific errors - Autopilot-specific errors - - - The system time is the time of the master clock, typically the computer clock of the main onboard computer. - Timestamp of the master clock in microseconds since UNIX epoch. - Timestamp of the component clock since boot time in milliseconds. - - - - A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. - Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - PING sequence - 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - - - Request to control this MAV - System the GCS requests control for - 0: request control of this MAV, 1: Release control of this MAV - 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - - - Accept / deny control of this MAV - ID of the GCS this message - 0: request control of this MAV, 1: Release control of this MAV - 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - - - Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. - key - - - THIS INTERFACE IS DEPRECATED. USE COMMAND_LONG with MAV_CMD_DO_SET_MODE INSTEAD. Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. - The system setting the mode - The new base mode - The new autopilot-specific mode. This field can be ignored by an autopilot. - - - - Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. - System ID - Component ID - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - - - Request all parameters of this component. After this request, all parameters are emitted. - System ID - Component ID - - - Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Onboard parameter value - Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - Total number of onboard parameters - Index of this onboard parameter - - - Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. - System ID - Component ID - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Onboard parameter value - Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - - - The global position, as returned by the Global Positioning System (GPS). This is - NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - See the GPS_FIX_TYPE enum. - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - Number of satellites visible. If unknown, set to 255 - - - The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. - Number of satellites visible - Global satellite ID - 0: Satellite not used, 1: used for localization - Elevation (0: right on top of receiver, 90: on the horizon) of satellite - Direction of satellite, 0: 0 deg, 255: 360 deg. - Signal to noise ratio of satellite - - - The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units - Timestamp (milliseconds since system boot) - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - Angular speed around X axis (millirad /sec) - Angular speed around Y axis (millirad /sec) - Angular speed around Z axis (millirad /sec) - X Magnetic field (milli tesla) - Y Magnetic field (milli tesla) - Z Magnetic field (milli tesla) - - - The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - X acceleration (raw) - Y acceleration (raw) - Z acceleration (raw) - Angular speed around X axis (raw) - Angular speed around Y axis (raw) - Angular speed around Z axis (raw) - X Magnetic field (raw) - Y Magnetic field (raw) - Z Magnetic field (raw) - - - The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Absolute pressure (raw) - Differential pressure 1 (raw, 0 if nonexistant) - Differential pressure 2 (raw, 0 if nonexistant) - Raw Temperature measurement (raw) - - - The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. - Timestamp (milliseconds since system boot) - Absolute pressure (hectopascal) - Differential pressure 1 (hectopascal) - Temperature measurement (0.01 degrees celsius) - - - The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). - Timestamp (milliseconds since system boot) - Roll angle (rad, -pi..+pi) - Pitch angle (rad, -pi..+pi) - Yaw angle (rad, -pi..+pi) - Roll angular speed (rad/s) - Pitch angular speed (rad/s) - Yaw angular speed (rad/s) - - - The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). - Timestamp (milliseconds since system boot) - Quaternion component 1, w (1 in null-rotation) - Quaternion component 2, x (0 in null-rotation) - Quaternion component 3, y (0 in null-rotation) - Quaternion component 4, z (0 in null-rotation) - Roll angular speed (rad/s) - Pitch angular speed (rad/s) - Yaw angular speed (rad/s) - - - The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - Timestamp (milliseconds since system boot) - X Position - Y Position - Z Position - X Speed - Y Speed - Z Speed - - - The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It - is designed as scaled integer message since the resolution of float is not sufficient. - Timestamp (milliseconds since system boot) - Latitude, expressed as degrees * 1E7 - Longitude, expressed as degrees * 1E7 - Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - Altitude above ground in meters, expressed as * 1000 (millimeters) - Ground X Speed (Latitude, positive north), expressed as m/s * 100 - Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - - - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX. - Timestamp (milliseconds since system boot) - Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - - - The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - Timestamp (milliseconds since system boot) - Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - - - The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. - Timestamp (microseconds since system boot) - Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - Servo output 1 value, in microseconds - Servo output 2 value, in microseconds - Servo output 3 value, in microseconds - Servo output 4 value, in microseconds - Servo output 5 value, in microseconds - Servo output 6 value, in microseconds - Servo output 7 value, in microseconds - Servo output 8 value, in microseconds - - Servo output 9 value, in microseconds - Servo output 10 value, in microseconds - Servo output 11 value, in microseconds - Servo output 12 value, in microseconds - Servo output 13 value, in microseconds - Servo output 14 value, in microseconds - Servo output 15 value, in microseconds - Servo output 16 value, in microseconds - - - Request a partial list of mission items from the system/component. http://qgroundcontrol.org/mavlink/waypoint_protocol. If start and end index are the same, just send one waypoint. - System ID - Component ID - Start index, 0 by default - End index, -1 by default (-1: send list to end). Else a valid index of the list - - Mission type, see MAV_MISSION_TYPE - - - This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED! - System ID - Component ID - Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - End index, equal or greater than start index. - - Mission type, see MAV_MISSION_TYPE - - - Message encoding a mission item. This message is emitted to announce - the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See also http://qgroundcontrol.org/mavlink/waypoint_protocol. - System ID - Component ID - Sequence - The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - false:0, true:1 - autocontinue to next wp - PARAM1, see MAV_CMD enum - PARAM2, see MAV_CMD enum - PARAM3, see MAV_CMD enum - PARAM4, see MAV_CMD enum - PARAM5 / local: x position, global: latitude - PARAM6 / y position: global: longitude - PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - - Mission type, see MAV_MISSION_TYPE - - - Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol - System ID - Component ID - Sequence - - Mission type, see MAV_MISSION_TYPE - - - Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between). - System ID - Component ID - Sequence - - - Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item. - Sequence - - - Request the overall list of mission items from the system/component. - System ID - Component ID - - Mission type, see MAV_MISSION_TYPE - - - This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs. - System ID - Component ID - Number of mission items in the sequence - - Mission type, see MAV_MISSION_TYPE - - - Delete all mission items at once. - System ID - Component ID - - Mission type, see MAV_MISSION_TYPE - - - A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION. - Sequence - - - Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). - System ID - Component ID - See MAV_MISSION_RESULT enum - - Mission type, see MAV_MISSION_TYPE - - - As local waypoints exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. - System ID - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84, in degrees * 1E7 - Altitude (AMSL), in meters * 1000 (positive for up) - - - Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (AMSL), in meters * 1000 (positive for up) - - - Bind a RC channel to a parameter. The parameter should change accoding to the RC channel value. - System ID - Component ID - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - Initial parameter value - Scale, maps the RC range [-1, 1] to a parameter value - Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - - - Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. http://qgroundcontrol.org/mavlink/waypoint_protocol - System ID - Component ID - Sequence - - Mission type, see MAV_MISSION_TYPE - - - Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations. - System ID - Component ID - Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - x position 1 / Latitude 1 - y position 1 / Longitude 1 - z position 1 / Altitude 1 - x position 2 / Latitude 2 - y position 2 / Longitude 2 - z position 2 / Altitude 2 - - - Read out the safety zone the MAV currently assumes. - Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - x position 1 / Latitude 1 - y position 1 / Longitude 1 - z position 1 / Altitude 1 - x position 2 / Latitude 2 - y position 2 / Longitude 2 - z position 2 / Altitude 2 - - - The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). - Timestamp (microseconds since system boot or since UNIX epoch) - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - Roll angular speed (rad/s) - Pitch angular speed (rad/s) - Yaw angular speed (rad/s) - Attitude covariance - - - The state of the fixed wing navigation and position controller. - Current desired roll in degrees - Current desired pitch in degrees - Current desired heading in degrees - Bearing to current MISSION/target in degrees - Distance to active MISSION in meters - Current altitude error in meters - Current airspeed error in meters/second - Current crosstrack error on x-y plane in meters - - - The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset. - Timestamp (microseconds since system boot or since UNIX epoch) - Class id of the estimator this estimate originated from. - Latitude, expressed as degrees * 1E7 - Longitude, expressed as degrees * 1E7 - Altitude in meters, expressed as * 1000 (millimeters), above MSL - Altitude above ground in meters, expressed as * 1000 (millimeters) - Ground X Speed (Latitude), expressed as m/s - Ground Y Speed (Longitude), expressed as m/s - Ground Z Speed (Altitude), expressed as m/s - Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) - - - The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - Timestamp (microseconds since system boot or since UNIX epoch) - Class id of the estimator this estimate originated from. - X Position - Y Position - Z Position - X Speed (m/s) - Y Speed (m/s) - Z Speed (m/s) - X Acceleration (m/s^2) - Y Acceleration (m/s^2) - Z Acceleration (m/s^2) - Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) - - - The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - Timestamp (milliseconds since system boot) - Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - - - THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. - The target requested to send the message stream. - The target requested to send the message stream. - The ID of the requested data stream - The requested message rate - 1 to start sending, 0 to stop sending. - - - THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. - The ID of the requested data stream - The message rate - 1 stream is enabled, 0 stream is stopped. - - - This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled an buttons are also transmit as boolean values of their - The system to be controlled. - X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - - - The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16_MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - System ID - Component ID - RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - - - Message encoding a mission item. This message is emitted to announce - the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See alsohttp://qgroundcontrol.org/mavlink/waypoint_protocol. - System ID - Component ID - Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - false:0, true:1 - autocontinue to next wp - PARAM1, see MAV_CMD enum - PARAM2, see MAV_CMD enum - PARAM3, see MAV_CMD enum - PARAM4, see MAV_CMD enum - PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - - Mission type, see MAV_MISSION_TYPE - - - Metrics typically displayed on a HUD for fixed wing aircraft - Current airspeed in m/s - Current ground speed in m/s - Current heading in degrees, in compass units (0..360, 0=north) - Current throttle setting in integer percent, 0 to 100 - Current altitude (MSL), in meters - Current climb rate in meters/second - - - Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value. - System ID - Component ID - The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - false:0, true:1 - autocontinue to next wp - PARAM1, see MAV_CMD enum - PARAM2, see MAV_CMD enum - PARAM3, see MAV_CMD enum - PARAM4, see MAV_CMD enum - PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - - - Send a command with up to seven parameters to the MAV - System which should execute the command - Component which should execute the command, 0 for all components - Command ID, as defined by MAV_CMD enum. - 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - Parameter 1, as defined by MAV_CMD enum. - Parameter 2, as defined by MAV_CMD enum. - Parameter 3, as defined by MAV_CMD enum. - Parameter 4, as defined by MAV_CMD enum. - Parameter 5, as defined by MAV_CMD enum. - Parameter 6, as defined by MAV_CMD enum. - Parameter 7, as defined by MAV_CMD enum. - - - Report status of a command. Includes feedback wether the command was executed. - Command ID, as defined by MAV_CMD enum. - See MAV_RESULT enum - - WIP: Needs to be set when MAV_RESULT is MAV_RESULT_IN_PROGRESS, values from 0 to 100 for progress percentage, 255 for unknown progress. - - - Setpoint in roll, pitch, yaw and thrust from the operator - Timestamp in milliseconds since system boot - Desired roll rate in radians per second - Desired pitch rate in radians per second - Desired yaw rate in radians per second - Collective thrust, normalized to 0 .. 1 - Flight mode switch position, 0.. 255 - Override mode switch position, 0.. 255 - - - Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system). - Timestamp in milliseconds since system boot - System ID - Component ID - Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - Body roll rate in radians per second - Body roll rate in radians per second - Body roll rate in radians per second - Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - - - Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way. - Timestamp in milliseconds since system boot - Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - Body roll rate in radians per second - Body pitch rate in radians per second - Body yaw rate in radians per second - Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - - - Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system). - Timestamp in milliseconds since system boot - System ID - Component ID - Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - X Position in NED frame in meters - Y Position in NED frame in meters - Z Position in NED frame in meters (note, altitude is negative in NED) - X velocity in NED frame in meter / s - Y velocity in NED frame in meter / s - Z velocity in NED frame in meter / s - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint in rad - yaw rate setpoint in rad/s - - - Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way. - Timestamp in milliseconds since system boot - Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - X Position in NED frame in meters - Y Position in NED frame in meters - Z Position in NED frame in meters (note, altitude is negative in NED) - X velocity in NED frame in meter / s - Y velocity in NED frame in meter / s - Z velocity in NED frame in meter / s - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint in rad - yaw rate setpoint in rad/s - - - Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system). - Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - System ID - Component ID - Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - X Position in WGS84 frame in 1e7 * meters - Y Position in WGS84 frame in 1e7 * meters - Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - X velocity in NED frame in meter / s - Y velocity in NED frame in meter / s - Z velocity in NED frame in meter / s - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint in rad - yaw rate setpoint in rad/s - - - Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way. - Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - X Position in WGS84 frame in 1e7 * meters - Y Position in WGS84 frame in 1e7 * meters - Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - X velocity in NED frame in meter / s - Y velocity in NED frame in meter / s - Z velocity in NED frame in meter / s - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint in rad - yaw rate setpoint in rad/s - - - The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - Timestamp (milliseconds since system boot) - X Position - Y Position - Z Position - Roll - Pitch - Yaw - - - DEPRECATED PACKET! Suffers from missing airspeed fields and singularities due to Euler angles. Please use HIL_STATE_QUATERNION instead. Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Roll angle (rad) - Pitch angle (rad) - Yaw angle (rad) - Body frame roll / phi angular speed (rad/s) - Body frame pitch / theta angular speed (rad/s) - Body frame yaw / psi angular speed (rad/s) - Latitude, expressed as * 1E7 - Longitude, expressed as * 1E7 - Altitude in meters, expressed as * 1000 (millimeters) - Ground X Speed (Latitude), expressed as m/s * 100 - Ground Y Speed (Longitude), expressed as m/s * 100 - Ground Z Speed (Altitude), expressed as m/s * 100 - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - - - Sent from autopilot to simulation. Hardware in the loop control outputs - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Control output -1 .. 1 - Control output -1 .. 1 - Control output -1 .. 1 - Throttle 0 .. 1 - Aux 1, -1 .. 1 - Aux 2, -1 .. 1 - Aux 3, -1 .. 1 - Aux 4, -1 .. 1 - System mode (MAV_MODE) - Navigation mode (MAV_NAV_MODE) - - - Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - RC channel 1 value, in microseconds - RC channel 2 value, in microseconds - RC channel 3 value, in microseconds - RC channel 4 value, in microseconds - RC channel 5 value, in microseconds - RC channel 6 value, in microseconds - RC channel 7 value, in microseconds - RC channel 8 value, in microseconds - RC channel 9 value, in microseconds - RC channel 10 value, in microseconds - RC channel 11 value, in microseconds - RC channel 12 value, in microseconds - Receive signal strength indicator, 0: 0%, 255: 100% - - - Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS) - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - System mode (MAV_MODE), includes arming state. - Flags as bitfield, reserved for future use. - - - Optical flow from a flow sensor (e.g. optical mouse sensor) - Timestamp (UNIX) - Sensor ID - Flow in pixels * 10 in x-sensor direction (dezi-pixels) - Flow in pixels * 10 in y-sensor direction (dezi-pixels) - Flow in meters in x-sensor direction, angular-speed compensated - Flow in meters in y-sensor direction, angular-speed compensated - Optical flow quality / confidence. 0: bad, 255: maximum quality - Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - - Flow rate in radians/second about X axis - Flow rate in radians/second about Y axis - - - Timestamp (microseconds, synced to UNIX time or since system boot) - Global X position - Global Y position - Global Z position - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - - - Timestamp (microseconds, synced to UNIX time or since system boot) - Global X position - Global Y position - Global Z position - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - - - Timestamp (microseconds, synced to UNIX time or since system boot) - Global X speed - Global Y speed - Global Z speed - - - Timestamp (microseconds, synced to UNIX time or since system boot) - Global X position - Global Y position - Global Z position - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - - - The IMU readings in SI units in NED body frame - Timestamp (microseconds, synced to UNIX time or since system boot) - X acceleration (m/s^2) - Y acceleration (m/s^2) - Z acceleration (m/s^2) - Angular speed around X axis (rad / sec) - Angular speed around Y axis (rad / sec) - Angular speed around Z axis (rad / sec) - X Magnetic field (Gauss) - Y Magnetic field (Gauss) - Z Magnetic field (Gauss) - Absolute pressure in millibar - Differential pressure in millibar - Altitude calculated from pressure - Temperature in degrees celsius - Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - - - Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor) - Timestamp (microseconds, synced to UNIX time or since system boot) - Sensor ID - Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - RH rotation around X axis (rad) - RH rotation around Y axis (rad) - RH rotation around Z axis (rad) - Temperature * 100 in centi-degrees Celsius - Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - Time in microseconds since the distance was sampled. - Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - - - The IMU readings in SI units in NED body frame - Timestamp (microseconds, synced to UNIX time or since system boot) - X acceleration (m/s^2) - Y acceleration (m/s^2) - Z acceleration (m/s^2) - Angular speed around X axis in body frame (rad / sec) - Angular speed around Y axis in body frame (rad / sec) - Angular speed around Z axis in body frame (rad / sec) - X Magnetic field (Gauss) - Y Magnetic field (Gauss) - Z Magnetic field (Gauss) - Absolute pressure in millibar - Differential pressure (airspeed) in millibar - Altitude calculated from pressure - Temperature in degrees celsius - Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. - - - Status of simulation environment, if used - True attitude quaternion component 1, w (1 in null-rotation) - True attitude quaternion component 2, x (0 in null-rotation) - True attitude quaternion component 3, y (0 in null-rotation) - True attitude quaternion component 4, z (0 in null-rotation) - Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - X acceleration m/s/s - Y acceleration m/s/s - Z acceleration m/s/s - Angular speed around X axis rad/s - Angular speed around Y axis rad/s - Angular speed around Z axis rad/s - Latitude in degrees - Longitude in degrees - Altitude in meters - Horizontal position standard deviation - Vertical position standard deviation - True velocity in m/s in NORTH direction in earth-fixed NED frame - True velocity in m/s in EAST direction in earth-fixed NED frame - True velocity in m/s in DOWN direction in earth-fixed NED frame - - - Status generated by radio and injected into MAVLink stream. - Local signal strength - Remote signal strength - Remaining free buffer space in percent. - Background noise level - Remote background noise level - Receive errors - Count of error corrected packets - - - File transfer message - Network ID (0 for broadcast) - System ID (0 for broadcast) - Component ID (0 for broadcast) - Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - - - Time synchronization message. - Time sync timestamp 1 - Time sync timestamp 2 - - - Camera-IMU triggering and synchronisation message. - Timestamp for the image frame in microseconds - Image frame sequence - - - The global position, as returned by the Global Positioning System (GPS). This is - NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - GPS ground speed in cm/s. If unknown, set to: 65535 - GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - GPS velocity in cm/s in EAST direction in earth-fixed NED frame - GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - Number of satellites visible. If unknown, set to 255 - - - Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor) - Timestamp (microseconds, synced to UNIX time or since system boot) - Sensor ID - Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - RH rotation around X axis (rad) - RH rotation around Y axis (rad) - RH rotation around Z axis (rad) - Temperature * 100 in centi-degrees Celsius - Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - Time in microseconds since the distance was sampled. - Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - - - Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - Body frame roll / phi angular speed (rad/s) - Body frame pitch / theta angular speed (rad/s) - Body frame yaw / psi angular speed (rad/s) - Latitude, expressed as * 1E7 - Longitude, expressed as * 1E7 - Altitude in meters, expressed as * 1000 (millimeters) - Ground X Speed (Latitude), expressed as cm/s - Ground Y Speed (Longitude), expressed as cm/s - Ground Z Speed (Altitude), expressed as cm/s - Indicated airspeed, expressed as cm/s - True airspeed, expressed as cm/s - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - - - The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units - Timestamp (milliseconds since system boot) - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - Angular speed around X axis (millirad /sec) - Angular speed around Y axis (millirad /sec) - Angular speed around Z axis (millirad /sec) - X Magnetic field (milli tesla) - Y Magnetic field (milli tesla) - Z Magnetic field (milli tesla) - - - Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. - System ID - Component ID - First log id (0 for first available) - Last log id (0xffff for last available) - - - Reply to LOG_REQUEST_LIST - Log id - Total number of logs - High log number - UTC timestamp of log in seconds since 1970, or 0 if not available - Size of the log (may be approximate) in bytes - - - Request a chunk of a log - System ID - Component ID - Log id (from LOG_ENTRY reply) - Offset into the log - Number of bytes - - - Reply to LOG_REQUEST_DATA - Log id (from LOG_ENTRY reply) - Offset into the log - Number of bytes (zero for end of log) - log data - - - Erase all logs - System ID - Component ID - - - Stop log transfer and resume normal logging - System ID - Component ID - - - data for injecting into the onboard GPS (used for DGPS) - System ID - Component ID - data length - raw data (110 is enough for 12 satellites of RTCMv2) - - - Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS frame). - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - See the GPS_FIX_TYPE enum. - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - Number of satellites visible. If unknown, set to 255 - Number of DGPS satellites - Age of DGPS info - - - Power supply status - 5V rail voltage in millivolts - servo rail voltage in millivolts - power supply status flags (see MAV_POWER_STATUS enum) - - - Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate. - See SERIAL_CONTROL_DEV enum - See SERIAL_CONTROL_FLAG enum - Timeout for reply data in milliseconds - Baudrate of transfer. Zero means no change. - how many bytes in this transfer - serial data - - - RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting - Time since boot of last baseline message received in ms. - Identification of connected RTK receiver. - GPS Week Number of last baseline - GPS Time of Week of last baseline - GPS-specific health report for RTK data. - Rate of baseline messages being received by GPS, in HZ - Current number of sats used for RTK calculation. - Coordinate system of baseline. 0 == ECEF, 1 == NED - Current baseline in ECEF x or NED north component in mm. - Current baseline in ECEF y or NED east component in mm. - Current baseline in ECEF z or NED down component in mm. - Current estimate of baseline accuracy. - Current number of integer ambiguity hypotheses. - - - RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting - Time since boot of last baseline message received in ms. - Identification of connected RTK receiver. - GPS Week Number of last baseline - GPS Time of Week of last baseline - GPS-specific health report for RTK data. - Rate of baseline messages being received by GPS, in HZ - Current number of sats used for RTK calculation. - Coordinate system of baseline. 0 == ECEF, 1 == NED - Current baseline in ECEF x or NED north component in mm. - Current baseline in ECEF y or NED east component in mm. - Current baseline in ECEF z or NED down component in mm. - Current estimate of baseline accuracy. - Current number of integer ambiguity hypotheses. - - - The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units - Timestamp (milliseconds since system boot) - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - Angular speed around X axis (millirad /sec) - Angular speed around Y axis (millirad /sec) - Angular speed around Z axis (millirad /sec) - X Magnetic field (milli tesla) - Y Magnetic field (milli tesla) - Z Magnetic field (milli tesla) - - - type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - total data size in bytes (set on ACK only) - Width of a matrix or image - Height of a matrix or image - number of packets beeing sent (set on ACK only) - payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - JPEG quality out of [1,100] - - - sequence number (starting with 0 on every transmission) - image data bytes - - - Time since system boot - Minimum distance the sensor can measure in centimeters - Maximum distance the sensor can measure in centimeters - Current distance reading - Type from MAV_DISTANCE_SENSOR enum. - Onboard ID of the sensor - Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - Measurement covariance in centimeters, 0 for unknown / invalid readings - - - Request for terrain data and terrain status - Latitude of SW corner of first grid (degrees *10^7) - Longitude of SW corner of first grid (in degrees *10^7) - Grid spacing in meters - Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - - - Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST - Latitude of SW corner of first grid (degrees *10^7) - Longitude of SW corner of first grid (in degrees *10^7) - Grid spacing in meters - bit within the terrain request mask - Terrain data in meters AMSL - - - Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission. - Latitude (degrees *10^7) - Longitude (degrees *10^7) - - - Response from a TERRAIN_CHECK request - Latitude (degrees *10^7) - Longitude (degrees *10^7) - grid spacing (zero if terrain at this location unavailable) - Terrain height in meters AMSL - Current vehicle height above lat/lon terrain height (meters) - Number of 4x4 terrain blocks waiting to be received or read from disk - Number of 4x4 terrain blocks in memory - - - Barometer readings for 2nd barometer - Timestamp (milliseconds since system boot) - Absolute pressure (hectopascal) - Differential pressure 1 (hectopascal) - Temperature measurement (0.01 degrees celsius) - - - Motion capture attitude and position - Timestamp (micros since boot or Unix epoch) - Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - X position in meters (NED) - Y position in meters (NED) - Z position in meters (NED) - - - Set the vehicle attitude and body angular rates. - Timestamp (micros since boot or Unix epoch) - Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - System ID - Component ID - Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - - - Set the vehicle attitude and body angular rates. - Timestamp (micros since boot or Unix epoch) - Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - - - The current system altitude. - Timestamp (micros since boot or Unix epoch) - This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - This is the altitude above the home position. It resets on each change of the current home position. - This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - - - The autopilot is requesting a resource (file, binary, other type of data) - Request ID. This ID should be re-used when sending back URI contents - The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - - - Barometer readings for 3rd barometer - Timestamp (milliseconds since system boot) - Absolute pressure (hectopascal) - Differential pressure 1 (hectopascal) - Temperature measurement (0.01 degrees celsius) - - - current motion information from a designated system - Timestamp in milliseconds since system boot - bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - AMSL, in meters - target velocity (0,0,0) for unknown - linear target acceleration (0,0,0) for unknown - (1 0 0 0 for unknown) - (0 0 0 for unknown) - eph epv - button states or switches of a tracker device - - - The smoothed, monotonic system state used to feed the control loops of the system. - Timestamp (micros since boot or Unix epoch) - X acceleration in body frame - Y acceleration in body frame - Z acceleration in body frame - X velocity in body frame - Y velocity in body frame - Z velocity in body frame - X position in local frame - Y position in local frame - Z position in local frame - Airspeed, set to -1 if unknown - Variance of body velocity estimate - Variance in local position - The attitude, represented as Quaternion - Angular rate in roll axis - Angular rate in pitch axis - Angular rate in yaw axis - - - Battery information - Battery ID - Function of the battery - Type (chemistry) of the battery - Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - - - Version and capability of autopilot software - bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - Firmware version number - Middleware version number - Operating system version number - HW / board version (last 8 bytes should be silicon ID, if any) - Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - ID of the board vendor - ID of the product - UID if provided by hardware - - - The location of a landing area captured from a downward facing camera - Timestamp (micros since boot or Unix epoch) - The ID of the target if multiple targets are present - MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - X-axis angular offset (in radians) of the target from the center of the image - Y-axis angular offset (in radians) of the target from the center of the image - Distance to the target from the vehicle in meters - Size in radians of target along x-axis - Size in radians of target along y-axis - - - - Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovaton test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovaton test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user. - Timestamp (micros since boot or Unix epoch) - Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - Velocity innovation test ratio - Horizontal position innovation test ratio - Vertical position innovation test ratio - Magnetometer innovation test ratio - Height above terrain innovation test ratio - True airspeed innovation test ratio - Horizontal position 1-STD accuracy relative to the EKF local origin (m) - Vertical position 1-STD accuracy relative to the EKF local origin (m) - - - Timestamp (micros since boot or Unix epoch) - Wind in X (NED) direction in m/s - Wind in Y (NED) direction in m/s - Wind in Z (NED) direction in m/s - Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - AMSL altitude (m) this measurement was taken at - Horizontal speed 1-STD accuracy - Vertical speed 1-STD accuracy - - - GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the sytem. - Timestamp (micros since boot or Unix epoch) - ID of the GPS for multiple GPS inputs - Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - GPS time (milliseconds from start of GPS week) - GPS week number - 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (AMSL, not WGS84), in m (positive for up) - GPS HDOP horizontal dilution of position in m - GPS VDOP vertical dilution of position in m - GPS velocity in m/s in NORTH direction in earth-fixed NED frame - GPS velocity in m/s in EAST direction in earth-fixed NED frame - GPS velocity in m/s in DOWN direction in earth-fixed NED frame - GPS speed accuracy in m/s - GPS horizontal accuracy in m - GPS vertical accuracy in m - Number of satellites visible. - - - RTCM message for injecting into the onboard GPS (used for DGPS) - LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - data length - RTCM message (may be fragmented) - - - Message appropriate for high latency connections like Iridium - System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - A bitfield for use for autopilot-specific flags. - The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - roll (centidegrees) - pitch (centidegrees) - heading (centidegrees) - throttle (percentage) - heading setpoint (centidegrees) - Latitude, expressed as degrees * 1E7 - Longitude, expressed as degrees * 1E7 - Altitude above mean sea level (meters) - Altitude setpoint relative to the home position (meters) - airspeed (m/s) - airspeed setpoint (m/s) - groundspeed (m/s) - climb rate (m/s) - Number of satellites visible. If unknown, set to 255 - See the GPS_FIX_TYPE enum. - Remaining battery (percentage) - Autopilot temperature (degrees C) - Air temperature (degrees C) from airspeed sensor - failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - current waypoint number - distance to target (meters) - - - Vibration levels and accelerometer clipping - Timestamp (micros since boot or Unix epoch) - Vibration levels on X-axis - Vibration levels on Y-axis - Vibration levels on Z-axis - first accelerometer clipping count - second accelerometer clipping count - third accelerometer clipping count - - - This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The position the system will return to and land on. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84, in degrees * 1E7 - Altitude (AMSL), in meters * 1000 (positive for up) - Local X position of this position in the local coordinate frame - Local Y position of this position in the local coordinate frame - Local Z position of this position in the local coordinate frame - World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - - - The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. - System ID. - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84, in degrees * 1E7 - Altitude (AMSL), in meters * 1000 (positive for up) - Local X position of this position in the local coordinate frame - Local Y position of this position in the local coordinate frame - Local Z position of this position in the local coordinate frame - World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - - - This interface replaces DATA_STREAM - The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - - - Provides state for additional features - The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - - - The location and information of an ADSB vehicle - ICAO address - Latitude, expressed as degrees * 1E7 - Longitude, expressed as degrees * 1E7 - Type from ADSB_ALTITUDE_TYPE enum - Altitude(ASL) in millimeters - Course over ground in centidegrees - The horizontal velocity in centimeters/second - The vertical velocity in centimeters/second, positive is up - The callsign, 8+null - Type from ADSB_EMITTER_TYPE enum - Time since last communication in seconds - Flags to indicate various statuses including valid data fields - Squawk code - - - Information about a potential collision - Collision data source - Unique identifier, domain based on src field - Action that is being taken to avoid this collision - How concerned the aircraft is about this collision - Estimated time until collision occurs (seconds) - Closest vertical distance in meters between vehicle and object - Closest horizontal distance in meteres between vehicle and object - - - Message implementing parts of the V2 payload specs in V1 frames for transitional support. - Network ID (0 for broadcast) - System ID (0 for broadcast) - Component ID (0 for broadcast) - A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - - - Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - Starting address of the debug variables - Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - Memory contents at specified address - - - Name - Timestamp - x - y - z - - - Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - Timestamp (milliseconds since system boot) - Name of the debug variable - Floating point value - - - Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - Timestamp (milliseconds since system boot) - Name of the debug variable - Signed integer value - - - Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). - Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - Status text message, without null termination character - - - Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. - Timestamp (milliseconds since system boot) - index of debug variable - DEBUG value - - - - Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing - system id of the target - component ID of the target - signing key - initial timestamp - - - Report button state change - Timestamp (milliseconds since system boot) - Time of last change of button state - Bitmap state of buttons - - - Control vehicle tone generation (buzzer) - System ID - Component ID - tune in board specific format - - - WIP: Information about a camera - Timestamp (milliseconds since system boot) - Camera ID (1 for first, 2 for second, etc.) - Number of cameras - Name of the camera vendor - Name of the camera model - Version of the camera firmware - Focal length in mm - Image sensor size horizontal in mm - Image sensor size vertical in mm - Image resolution in pixels horizontal - Image resolution in pixels vertical - Reserved for a lens ID - - - WIP: Settings of a camera, can be requested using MAV_CMD_REQUEST_CAMERA_SETTINGS and written using MAV_CMD_SET_CAMERA_SETTINGS - Timestamp (milliseconds since system boot) - Camera ID (1 for first, 2 for second, etc.) - 0: full auto 1: full manual 2: aperture priority 3: shutter priority - Aperture is 1/value - Shutter speed in seconds - ISO sensitivity - Exposure Value - Color temperature in degrees Kelvin. (0: Auto WB) - Reserved for a camera mode ID. (0: Photo 1: Video) - Audio recording enabled (0: off 1: on) - Reserved for a color mode ID (Neutral, Vivid, etc.) - Reserved for image format ID (Jpeg/Raw/Jpeg+Raw) - Reserved for image quality ID (Compression) - Reserved for metering mode ID (Average, Center, Spot, etc.) - - - WIP: Information about a storage medium - Timestamp (milliseconds since system boot) - Storage ID (1 for first, 2 for second, etc.) - Number of storage devices - Status of storage (0 not available, 1 unformatted, 2 formatted) - Total capacity in MiB - Used capacity in MiB - Available capacity in MiB - Read speed in MiB/s - Write speed in MiB/s - - - WIP: Information about the status of a capture - Timestamp (milliseconds since system boot) - Camera ID (1 for first, 2 for second, etc.) - Current status of image capturing (0: not running, 1: interval capture in progress) - Current status of video capturing (0: not running, 1: capture in progress) - Image capture interval in seconds - Video frame rate in Hz - Image resolution in pixels horizontal - Image resolution in pixels vertical - Video resolution in pixels horizontal - Video resolution in pixels vertical - Time in milliseconds since recording started - Available storage capacity in MiB - - - WIP: Information about a captured image - Timestamp (milliseconds since system boot) - Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. - Camera ID (1 for first, 2 for second, etc.) - Latitude, expressed as degrees * 1E7 where image was taken - Longitude, expressed as degrees * 1E7 where capture was taken - Altitude in meters, expressed as * 1E3 (AMSL, not WGS84) where image was taken - Altitude above ground in meters, expressed as * 1E3 where image was taken - Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0) - Zero based index of this image (image count since armed -1) - Boolean indicating success (1) or failure (0) while capturing this image. - URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. - - - WIP: Information about flight since last arming - Timestamp (milliseconds since system boot) - Timestamp at arming (microseconds since UNIX epoch) in UTC, 0 for unknown - Timestamp at takeoff (microseconds since UNIX epoch) in UTC, 0 for unknown - Universally unique identifier (UUID) of flight, should correspond to name of logfiles - - - WIP: Orientation of a mount - Timestamp (milliseconds since system boot) - Roll in degrees - Pitch in degrees - Yaw in degrees - - - A message containing logged data (see also MAV_CMD_LOGGING_START) - system ID of the target - component ID of the target - sequence number (can wrap) - data length - offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - logged data - - - A message containing logged data which requires a LOGGING_ACK to be sent back - system ID of the target - component ID of the target - sequence number (can wrap) - data length - offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - logged data - - - An ack for a LOGGING_DATA_ACKED message - system ID of the target - component ID of the target - sequence number (must match the one in LOGGING_DATA_ACKED) - - - WIP: Information about video stream - Camera ID (1 for first, 2 for second, etc.) - Current status of video streaming (0: not running, 1: in progress) - Frames per second - Resolution horizontal in pixels - Resolution vertical in pixels - Bit rate in bits per second - Video image rotation clockwise - Video stream URI - - - WIP: Message that sets video stream settings - system ID of the target - component ID of the target - Camera ID (1 for first, 2 for second, etc.) - Frames per second (set to -1 for highest framerate possible) - Resolution horizontal in pixels (set to -1 for highest resolution possible) - Resolution vertical in pixels (set to -1 for highest resolution possible) - Bit rate in bits per second (set to -1 for auto) - Video image rotation clockwise (0-359 degrees) - Video stream URI - - - diff --git a/include/mavlink/v1.0/protocol.h b/include/mavlink/v1.0/protocol.h deleted file mode 100644 index 731bd3a..0000000 --- a/include/mavlink/v1.0/protocol.h +++ /dev/null @@ -1,339 +0,0 @@ -#ifndef _MAVLINK_PROTOCOL_H_ -#define _MAVLINK_PROTOCOL_H_ - -#include "string.h" -#include "mavlink_types.h" - -/* - If you want MAVLink on a system that is native big-endian, - you need to define NATIVE_BIG_ENDIAN -*/ -#ifdef NATIVE_BIG_ENDIAN -# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN) -#else -# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) -#endif - -#ifndef MAVLINK_STACK_BUFFER -#define MAVLINK_STACK_BUFFER 0 -#endif - -#ifndef MAVLINK_AVOID_GCC_STACK_BUG -# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) -#endif - -#ifndef MAVLINK_ASSERT -#define MAVLINK_ASSERT(x) -#endif - -#ifndef MAVLINK_START_UART_SEND -#define MAVLINK_START_UART_SEND(chan, length) -#endif - -#ifndef MAVLINK_END_UART_SEND -#define MAVLINK_END_UART_SEND(chan, length) -#endif - -/* option to provide alternative implementation of mavlink_helpers.h */ -#ifdef MAVLINK_SEPARATE_HELPERS - - #define MAVLINK_HELPER - - /* decls in sync with those in mavlink_helpers.h */ - #ifndef MAVLINK_GET_CHANNEL_STATUS - MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan); - #endif - MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan); - #if MAVLINK_CRC_EXTRA - MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra); - MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t min_length, uint8_t length, uint8_t crc_extra); - #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 min_length, uint8_t length, uint8_t crc_extra); - #endif - #else - MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - 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); - MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c); - MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, - mavlink_status_t* status, - uint8_t c, - mavlink_message_t* r_message, - mavlink_status_t* r_mavlink_status); - MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); - MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); - MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, - uint8_t* r_bit_index, uint8_t* buffer); - #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); - MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg); - #endif - -#else - - #define MAVLINK_HELPER static inline - #include "mavlink_helpers.h" - -#endif // MAVLINK_SEPARATE_HELPERS - -/** - * @brief Get the required buffer size for this message - */ -static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) -{ - return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; -} - -#if MAVLINK_NEED_BYTE_SWAP -static inline void byte_swap_2(char *dst, const char *src) -{ - dst[0] = src[1]; - dst[1] = src[0]; -} -static inline void byte_swap_4(char *dst, const char *src) -{ - dst[0] = src[3]; - dst[1] = src[2]; - dst[2] = src[1]; - dst[3] = src[0]; -} -static inline void byte_swap_8(char *dst, const char *src) -{ - dst[0] = src[7]; - dst[1] = src[6]; - dst[2] = src[5]; - dst[3] = src[4]; - dst[4] = src[3]; - dst[5] = src[2]; - dst[6] = src[1]; - dst[7] = src[0]; -} -#elif !MAVLINK_ALIGNED_FIELDS -static inline void byte_copy_2(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; -} -static inline void byte_copy_4(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; - dst[2] = src[2]; - dst[3] = src[3]; -} -static inline void byte_copy_8(char *dst, const char *src) -{ - memcpy(dst, src, 8); -} -#endif - -#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b -#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b -#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b - -#if MAVLINK_NEED_BYTE_SWAP -#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#elif !MAVLINK_ALIGNED_FIELDS -#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#else -#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b -#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b -#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b -#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b -#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b -#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b -#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b -#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b -#endif - -/* - like memcpy(), but if src is NULL, do a memset to zero -*/ -static inline void mav_array_memcpy(void *dest, const void *src, size_t n) -{ - if (src == NULL) { - memset(dest, 0, n); - } else { - memcpy(dest, src, n); - } -} - -/* - * Place a char array into a buffer - */ -static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -/* - * Place a uint8_t array into a buffer - */ -static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -/* - * Place a int8_t array into a buffer - */ -static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -#if MAVLINK_NEED_BYTE_SWAP -#define _MAV_PUT_ARRAY(TYPE, V) \ -static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ -{ \ - if (b == NULL) { \ - memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ - } else { \ - uint16_t i; \ - for (i=0; i - -/** - * - * CALCULATE THE CHECKSUM - * - */ - -#define X25_INIT_CRC 0xffff -#define X25_VALIDATE_CRC 0xf0b8 - -#ifndef HAVE_CRC_ACCUMULATE -/** - * @brief Accumulate the X.25 CRC by adding one char at a time. - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new char to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) -{ - /*Accumulate one byte of data into the CRC*/ - uint8_t tmp; - - tmp = data ^ (uint8_t)(*crcAccum &0xff); - tmp ^= (tmp<<4); - *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); -} -#endif - - -/** - * @brief Initiliaze the buffer for the X.25 CRC - * - * @param crcAccum the 16 bit X.25 CRC - */ -static inline void crc_init(uint16_t* crcAccum) -{ - *crcAccum = X25_INIT_CRC; -} - - -/** - * @brief Calculates the X.25 checksum on a byte buffer - * - * @param pBuffer buffer containing the byte array to hash - * @param length length of the byte array - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) -{ - uint16_t crcTmp; - crc_init(&crcTmp); - while (length--) { - crc_accumulate(*pBuffer++, &crcTmp); - } - return crcTmp; -} - - -/** - * @brief Accumulate the X.25 CRC by adding an array of bytes - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new bytes to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length) -{ - const uint8_t *p = (const uint8_t *)pBuffer; - while (length--) { - crc_accumulate(*p++, crcAccum); - } -} - -#if defined(MAVLINK_USE_CXX_NAMESPACE) || defined(__cplusplus) -} -#endif diff --git a/include/mavlink/v2.0/common/common.h b/include/mavlink/v2.0/common/common.h deleted file mode 100644 index 2744d96..0000000 --- a/include/mavlink/v2.0/common/common.h +++ /dev/null @@ -1,1039 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from common.xml - * @see http://mavlink.org - */ -#pragma once -#ifndef MAVLINK_COMMON_H -#define MAVLINK_COMMON_H - -#ifndef MAVLINK_H - #error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. -#endif - -#undef MAVLINK_THIS_XML_IDX -#define MAVLINK_THIS_XML_IDX 1 - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {{0, 50, 9, 0, 0, 0}, {1, 124, 31, 0, 0, 0}, {2, 137, 12, 0, 0, 0}, {4, 237, 14, 3, 12, 13}, {5, 217, 28, 1, 0, 0}, {6, 104, 3, 0, 0, 0}, {7, 119, 32, 0, 0, 0}, {11, 89, 6, 1, 4, 0}, {20, 214, 20, 3, 2, 3}, {21, 159, 2, 3, 0, 1}, {22, 220, 25, 0, 0, 0}, {23, 168, 23, 3, 4, 5}, {24, 24, 30, 0, 0, 0}, {25, 23, 101, 0, 0, 0}, {26, 170, 22, 0, 0, 0}, {27, 144, 26, 0, 0, 0}, {28, 67, 16, 0, 0, 0}, {29, 115, 14, 0, 0, 0}, {30, 39, 28, 0, 0, 0}, {31, 246, 32, 0, 0, 0}, {32, 185, 28, 0, 0, 0}, {33, 104, 28, 0, 0, 0}, {34, 237, 22, 0, 0, 0}, {35, 244, 22, 0, 0, 0}, {36, 222, 21, 0, 0, 0}, {37, 212, 6, 3, 4, 5}, {38, 9, 6, 3, 4, 5}, {39, 254, 37, 3, 32, 33}, {40, 230, 4, 3, 2, 3}, {41, 28, 4, 3, 2, 3}, {42, 28, 2, 0, 0, 0}, {43, 132, 2, 3, 0, 1}, {44, 221, 4, 3, 2, 3}, {45, 232, 2, 3, 0, 1}, {46, 11, 2, 0, 0, 0}, {47, 153, 3, 3, 0, 1}, {48, 41, 13, 1, 12, 0}, {49, 39, 12, 0, 0, 0}, {50, 78, 37, 3, 18, 19}, {51, 196, 4, 3, 2, 3}, {54, 15, 27, 3, 24, 25}, {55, 3, 25, 0, 0, 0}, {61, 167, 72, 0, 0, 0}, {62, 183, 26, 0, 0, 0}, {63, 119, 181, 0, 0, 0}, {64, 191, 225, 0, 0, 0}, {65, 118, 42, 0, 0, 0}, {66, 148, 6, 3, 2, 3}, {67, 21, 4, 0, 0, 0}, {69, 243, 11, 0, 0, 0}, {70, 124, 18, 3, 16, 17}, {73, 38, 37, 3, 32, 33}, {74, 20, 20, 0, 0, 0}, {75, 158, 35, 3, 30, 31}, {76, 152, 33, 3, 30, 31}, {77, 143, 3, 0, 0, 0}, {81, 106, 22, 0, 0, 0}, {82, 49, 39, 3, 36, 37}, {83, 22, 37, 0, 0, 0}, {84, 143, 53, 3, 50, 51}, {85, 140, 51, 0, 0, 0}, {86, 5, 53, 3, 50, 51}, {87, 150, 51, 0, 0, 0}, {89, 231, 28, 0, 0, 0}, {90, 183, 56, 0, 0, 0}, {91, 63, 42, 0, 0, 0}, {92, 54, 33, 0, 0, 0}, {93, 47, 81, 0, 0, 0}, {100, 175, 26, 0, 0, 0}, {101, 102, 32, 0, 0, 0}, {102, 158, 32, 0, 0, 0}, {103, 208, 20, 0, 0, 0}, {104, 56, 32, 0, 0, 0}, {105, 93, 62, 0, 0, 0}, {106, 138, 44, 0, 0, 0}, {107, 108, 64, 0, 0, 0}, {108, 32, 84, 0, 0, 0}, {109, 185, 9, 0, 0, 0}, {110, 84, 254, 3, 1, 2}, {111, 34, 16, 0, 0, 0}, {112, 174, 12, 0, 0, 0}, {113, 124, 36, 0, 0, 0}, {114, 237, 44, 0, 0, 0}, {115, 4, 64, 0, 0, 0}, {116, 76, 22, 0, 0, 0}, {117, 128, 6, 3, 4, 5}, {118, 56, 14, 0, 0, 0}, {119, 116, 12, 3, 10, 11}, {120, 134, 97, 0, 0, 0}, {121, 237, 2, 3, 0, 1}, {122, 203, 2, 3, 0, 1}, {123, 250, 113, 3, 0, 1}, {124, 87, 35, 0, 0, 0}, {125, 203, 6, 0, 0, 0}, {126, 220, 79, 0, 0, 0}, {127, 25, 35, 0, 0, 0}, {128, 226, 35, 0, 0, 0}, {129, 46, 22, 0, 0, 0}, {130, 29, 13, 0, 0, 0}, {131, 223, 255, 0, 0, 0}, {132, 85, 14, 0, 0, 0}, {133, 6, 18, 0, 0, 0}, {134, 229, 43, 0, 0, 0}, {135, 203, 8, 0, 0, 0}, {136, 1, 22, 0, 0, 0}, {137, 195, 14, 0, 0, 0}, {138, 109, 36, 0, 0, 0}, {139, 168, 43, 3, 41, 42}, {140, 181, 41, 0, 0, 0}, {141, 47, 32, 0, 0, 0}, {142, 72, 243, 0, 0, 0}, {143, 131, 14, 0, 0, 0}, {144, 127, 93, 0, 0, 0}, {146, 103, 100, 0, 0, 0}, {147, 154, 36, 0, 0, 0}, {148, 178, 60, 0, 0, 0}, {149, 200, 30, 0, 0, 0}, {230, 163, 42, 0, 0, 0}, {231, 105, 40, 0, 0, 0}, {232, 151, 63, 0, 0, 0}, {233, 35, 182, 0, 0, 0}, {234, 150, 40, 0, 0, 0}, {241, 90, 32, 0, 0, 0}, {242, 104, 52, 0, 0, 0}, {243, 85, 53, 1, 52, 0}, {244, 95, 6, 0, 0, 0}, {245, 130, 2, 0, 0, 0}, {246, 184, 38, 0, 0, 0}, {247, 81, 19, 0, 0, 0}, {248, 8, 254, 3, 3, 4}, {249, 204, 36, 0, 0, 0}, {250, 49, 30, 0, 0, 0}, {251, 170, 18, 0, 0, 0}, {252, 44, 18, 0, 0, 0}, {253, 83, 51, 0, 0, 0}, {254, 46, 9, 0, 0, 0}, {256, 71, 42, 3, 8, 9}, {257, 131, 9, 0, 0, 0}, {258, 187, 32, 3, 0, 1}, {259, 122, 86, 0, 0, 0}, {260, 8, 28, 0, 0, 0}, {261, 244, 26, 0, 0, 0}, {262, 69, 31, 0, 0, 0}, {263, 133, 255, 0, 0, 0}, {264, 49, 28, 0, 0, 0}, {265, 26, 16, 0, 0, 0}, {266, 193, 255, 3, 2, 3}, {267, 35, 255, 3, 2, 3}, {268, 14, 4, 3, 2, 3}} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_COMMON - -// ENUM DEFINITIONS - - -/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */ -#ifndef HAVE_ENUM_MAV_AUTOPILOT -#define HAVE_ENUM_MAV_AUTOPILOT -typedef enum MAV_AUTOPILOT -{ - MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */ - MAV_AUTOPILOT_RESERVED=1, /* Reserved for future use. | */ - MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */ - MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */ - MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */ - MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */ - MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */ - MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */ - MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */ - MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */ - MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */ - MAV_AUTOPILOT_FP=11, /* FlexiPilot | */ - MAV_AUTOPILOT_PX4=12, /* PX4 Autopilot - http://pixhawk.ethz.ch/px4/ | */ - MAV_AUTOPILOT_SMACCMPILOT=13, /* SMACCMPilot - http://smaccmpilot.org | */ - MAV_AUTOPILOT_AUTOQUAD=14, /* AutoQuad -- http://autoquad.org | */ - MAV_AUTOPILOT_ARMAZILA=15, /* Armazila -- http://armazila.com | */ - MAV_AUTOPILOT_AEROB=16, /* Aerob -- http://aerob.ru | */ - MAV_AUTOPILOT_ASLUAV=17, /* ASLUAV autopilot -- http://www.asl.ethz.ch | */ - MAV_AUTOPILOT_ENUM_END=18, /* | */ -} MAV_AUTOPILOT; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_TYPE -#define HAVE_ENUM_MAV_TYPE -typedef enum MAV_TYPE -{ - MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */ - MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ - MAV_TYPE_QUADROTOR=2, /* Quadrotor | */ - MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */ - MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */ - MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */ - MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */ - MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */ - MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */ - MAV_TYPE_ROCKET=9, /* Rocket | */ - MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */ - MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */ - MAV_TYPE_SUBMARINE=12, /* Submarine | */ - MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */ - MAV_TYPE_OCTOROTOR=14, /* Octorotor | */ - MAV_TYPE_TRICOPTER=15, /* Tricopter | */ - MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */ - MAV_TYPE_KITE=17, /* Kite | */ - MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */ - MAV_TYPE_VTOL_DUOROTOR=19, /* Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. | */ - MAV_TYPE_VTOL_QUADROTOR=20, /* Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. | */ - MAV_TYPE_VTOL_TILTROTOR=21, /* Tiltrotor VTOL | */ - MAV_TYPE_VTOL_RESERVED2=22, /* VTOL reserved 2 | */ - MAV_TYPE_VTOL_RESERVED3=23, /* VTOL reserved 3 | */ - MAV_TYPE_VTOL_RESERVED4=24, /* VTOL reserved 4 | */ - MAV_TYPE_VTOL_RESERVED5=25, /* VTOL reserved 5 | */ - MAV_TYPE_GIMBAL=26, /* Onboard gimbal | */ - MAV_TYPE_ADSB=27, /* Onboard ADSB peripheral | */ - MAV_TYPE_ENUM_END=28, /* | */ -} MAV_TYPE; -#endif - -/** @brief These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. */ -#ifndef HAVE_ENUM_FIRMWARE_VERSION_TYPE -#define HAVE_ENUM_FIRMWARE_VERSION_TYPE -typedef enum FIRMWARE_VERSION_TYPE -{ - FIRMWARE_VERSION_TYPE_DEV=0, /* development release | */ - FIRMWARE_VERSION_TYPE_ALPHA=64, /* alpha release | */ - FIRMWARE_VERSION_TYPE_BETA=128, /* beta release | */ - FIRMWARE_VERSION_TYPE_RC=192, /* release candidate | */ - FIRMWARE_VERSION_TYPE_OFFICIAL=255, /* official stable release | */ - FIRMWARE_VERSION_TYPE_ENUM_END=256, /* | */ -} FIRMWARE_VERSION_TYPE; -#endif - -/** @brief These flags encode the MAV mode. */ -#ifndef HAVE_ENUM_MAV_MODE_FLAG -#define HAVE_ENUM_MAV_MODE_FLAG -typedef enum MAV_MODE_FLAG -{ - MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */ - MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ - MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */ - MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */ - MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */ - MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */ - MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */ - MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state. | */ - MAV_MODE_FLAG_ENUM_END=129, /* | */ -} MAV_MODE_FLAG; -#endif - -/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */ -#ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION -#define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION -typedef enum MAV_MODE_FLAG_DECODE_POSITION -{ - MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */ - MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */ - MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit: 00000100 | */ - MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */ - MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */ - MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */ - MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */ - MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */ - MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */ -} MAV_MODE_FLAG_DECODE_POSITION; -#endif - -/** @brief Override command, pauses current mission execution and moves immediately to a position */ -#ifndef HAVE_ENUM_MAV_GOTO -#define HAVE_ENUM_MAV_GOTO -typedef enum MAV_GOTO -{ - MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */ - MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */ - MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */ - MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */ - MAV_GOTO_ENUM_END=4, /* | */ -} MAV_GOTO; -#endif - -/** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it - simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */ -#ifndef HAVE_ENUM_MAV_MODE -#define HAVE_ENUM_MAV_MODE -typedef enum MAV_MODE -{ - MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */ - MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */ - MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ - MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */ - MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ - MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */ - MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ - MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */ - MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ - MAV_MODE_ENUM_END=221, /* | */ -} MAV_MODE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_STATE -#define HAVE_ENUM_MAV_STATE -typedef enum MAV_STATE -{ - MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */ - MAV_STATE_BOOT=1, /* System is booting up. | */ - MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */ - MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */ - MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */ - MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */ - MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */ - MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */ - MAV_STATE_ENUM_END=8, /* | */ -} MAV_STATE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_COMPONENT -#define HAVE_ENUM_MAV_COMPONENT -typedef enum MAV_COMPONENT -{ - MAV_COMP_ID_ALL=0, /* | */ - MAV_COMP_ID_CAMERA=100, /* | */ - MAV_COMP_ID_SERVO1=140, /* | */ - MAV_COMP_ID_SERVO2=141, /* | */ - MAV_COMP_ID_SERVO3=142, /* | */ - MAV_COMP_ID_SERVO4=143, /* | */ - MAV_COMP_ID_SERVO5=144, /* | */ - MAV_COMP_ID_SERVO6=145, /* | */ - MAV_COMP_ID_SERVO7=146, /* | */ - MAV_COMP_ID_SERVO8=147, /* | */ - MAV_COMP_ID_SERVO9=148, /* | */ - MAV_COMP_ID_SERVO10=149, /* | */ - MAV_COMP_ID_SERVO11=150, /* | */ - MAV_COMP_ID_SERVO12=151, /* | */ - MAV_COMP_ID_SERVO13=152, /* | */ - MAV_COMP_ID_SERVO14=153, /* | */ - MAV_COMP_ID_GIMBAL=154, /* | */ - MAV_COMP_ID_LOG=155, /* | */ - MAV_COMP_ID_ADSB=156, /* | */ - MAV_COMP_ID_OSD=157, /* On Screen Display (OSD) devices for video links | */ - MAV_COMP_ID_PERIPHERAL=158, /* Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol | */ - MAV_COMP_ID_QX1_GIMBAL=159, /* | */ - MAV_COMP_ID_MAPPER=180, /* | */ - MAV_COMP_ID_MISSIONPLANNER=190, /* | */ - MAV_COMP_ID_PATHPLANNER=195, /* | */ - MAV_COMP_ID_IMU=200, /* | */ - MAV_COMP_ID_IMU_2=201, /* | */ - MAV_COMP_ID_IMU_3=202, /* | */ - MAV_COMP_ID_GPS=220, /* | */ - MAV_COMP_ID_UDP_BRIDGE=240, /* | */ - MAV_COMP_ID_UART_BRIDGE=241, /* | */ - MAV_COMP_ID_SYSTEM_CONTROL=250, /* | */ - MAV_COMPONENT_ENUM_END=251, /* | */ -} MAV_COMPONENT; -#endif - -/** @brief These encode the sensors whose status is sent as part of the SYS_STATUS message. */ -#ifndef HAVE_ENUM_MAV_SYS_STATUS_SENSOR -#define HAVE_ENUM_MAV_SYS_STATUS_SENSOR -typedef enum MAV_SYS_STATUS_SENSOR -{ - MAV_SYS_STATUS_SENSOR_3D_GYRO=1, /* 0x01 3D gyro | */ - MAV_SYS_STATUS_SENSOR_3D_ACCEL=2, /* 0x02 3D accelerometer | */ - MAV_SYS_STATUS_SENSOR_3D_MAG=4, /* 0x04 3D magnetometer | */ - MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE=8, /* 0x08 absolute pressure | */ - MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE=16, /* 0x10 differential pressure | */ - MAV_SYS_STATUS_SENSOR_GPS=32, /* 0x20 GPS | */ - MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW=64, /* 0x40 optical flow | */ - MAV_SYS_STATUS_SENSOR_VISION_POSITION=128, /* 0x80 computer vision position | */ - MAV_SYS_STATUS_SENSOR_LASER_POSITION=256, /* 0x100 laser based position | */ - MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH=512, /* 0x200 external ground truth (Vicon or Leica) | */ - MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL=1024, /* 0x400 3D angular rate control | */ - MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION=2048, /* 0x800 attitude stabilization | */ - MAV_SYS_STATUS_SENSOR_YAW_POSITION=4096, /* 0x1000 yaw position | */ - MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL=8192, /* 0x2000 z/altitude control | */ - MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL=16384, /* 0x4000 x/y position control | */ - MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS=32768, /* 0x8000 motor outputs / control | */ - MAV_SYS_STATUS_SENSOR_RC_RECEIVER=65536, /* 0x10000 rc receiver | */ - MAV_SYS_STATUS_SENSOR_3D_GYRO2=131072, /* 0x20000 2nd 3D gyro | */ - MAV_SYS_STATUS_SENSOR_3D_ACCEL2=262144, /* 0x40000 2nd 3D accelerometer | */ - MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /* 0x80000 2nd 3D magnetometer | */ - MAV_SYS_STATUS_GEOFENCE=1048576, /* 0x100000 geofence | */ - MAV_SYS_STATUS_AHRS=2097152, /* 0x200000 AHRS subsystem health | */ - MAV_SYS_STATUS_TERRAIN=4194304, /* 0x400000 Terrain subsystem health | */ - MAV_SYS_STATUS_REVERSE_MOTOR=8388608, /* 0x800000 Motors are reversed | */ - MAV_SYS_STATUS_LOGGING=16777216, /* 0x1000000 Logging | */ - MAV_SYS_STATUS_SENSOR_BATTERY=33554432, /* 0x2000000 Battery | */ - MAV_SYS_STATUS_SENSOR_ENUM_END=33554433, /* | */ -} MAV_SYS_STATUS_SENSOR; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_FRAME -#define HAVE_ENUM_MAV_FRAME -typedef enum MAV_FRAME -{ - MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */ - MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */ - MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */ - MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */ - MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */ - MAV_FRAME_GLOBAL_INT=5, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) | */ - MAV_FRAME_GLOBAL_RELATIVE_ALT_INT=6, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. | */ - MAV_FRAME_LOCAL_OFFSET_NED=7, /* Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. | */ - MAV_FRAME_BODY_NED=8, /* Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. | */ - MAV_FRAME_BODY_OFFSET_NED=9, /* Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. | */ - MAV_FRAME_GLOBAL_TERRAIN_ALT=10, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ - MAV_FRAME_GLOBAL_TERRAIN_ALT_INT=11, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ - MAV_FRAME_ENUM_END=12, /* | */ -} MAV_FRAME; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE -#define HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE -typedef enum MAVLINK_DATA_STREAM_TYPE -{ - MAVLINK_DATA_STREAM_IMG_JPEG=1, /* | */ - MAVLINK_DATA_STREAM_IMG_BMP=2, /* | */ - MAVLINK_DATA_STREAM_IMG_RAW8U=3, /* | */ - MAVLINK_DATA_STREAM_IMG_RAW32U=4, /* | */ - MAVLINK_DATA_STREAM_IMG_PGM=5, /* | */ - MAVLINK_DATA_STREAM_IMG_PNG=6, /* | */ - MAVLINK_DATA_STREAM_TYPE_ENUM_END=7, /* | */ -} MAVLINK_DATA_STREAM_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_FENCE_ACTION -#define HAVE_ENUM_FENCE_ACTION -typedef enum FENCE_ACTION -{ - FENCE_ACTION_NONE=0, /* Disable fenced mode | */ - FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */ - FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */ - FENCE_ACTION_GUIDED_THR_PASS=3, /* Switched to guided mode to return point (fence point 0) with manual throttle control | */ - FENCE_ACTION_RTL=4, /* Switch to RTL (return to launch) mode and head for the return point. | */ - FENCE_ACTION_ENUM_END=5, /* | */ -} FENCE_ACTION; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_FENCE_BREACH -#define HAVE_ENUM_FENCE_BREACH -typedef enum FENCE_BREACH -{ - FENCE_BREACH_NONE=0, /* No last fence breach | */ - FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */ - FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */ - FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */ - FENCE_BREACH_ENUM_END=4, /* | */ -} FENCE_BREACH; -#endif - -/** @brief Enumeration of possible mount operation modes */ -#ifndef HAVE_ENUM_MAV_MOUNT_MODE -#define HAVE_ENUM_MAV_MOUNT_MODE -typedef enum MAV_MOUNT_MODE -{ - MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */ - MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */ - MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */ - MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */ - MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */ - MAV_MOUNT_MODE_ENUM_END=5, /* | */ -} MAV_MOUNT_MODE; -#endif - -/** @brief THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a - recommendation to the autopilot software. Individual autopilots may or may not obey - the recommended messages. */ -#ifndef HAVE_ENUM_MAV_DATA_STREAM -#define HAVE_ENUM_MAV_DATA_STREAM -typedef enum MAV_DATA_STREAM -{ - MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ - MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ - MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ - MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ - MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ - MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */ - MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_ENUM_END=13, /* | */ -} MAV_DATA_STREAM; -#endif - -/** @brief The ROI (region of interest) for the vehicle. This can be - be used by the vehicle for camera/vehicle attitude alignment (see - MAV_CMD_NAV_ROI). */ -#ifndef HAVE_ENUM_MAV_ROI -#define HAVE_ENUM_MAV_ROI -typedef enum MAV_ROI -{ - MAV_ROI_NONE=0, /* No region of interest. | */ - MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */ - MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */ - MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ - MAV_ROI_TARGET=4, /* Point toward of given id. | */ - MAV_ROI_ENUM_END=5, /* | */ -} MAV_ROI; -#endif - -/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */ -#ifndef HAVE_ENUM_MAV_CMD_ACK -#define HAVE_ENUM_MAV_CMD_ACK -typedef enum MAV_CMD_ACK -{ - MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */ - MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ - MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */ - MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */ - MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */ - MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */ - MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */ - MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */ - MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */ - MAV_CMD_ACK_ENUM_END=10, /* | */ -} MAV_CMD_ACK; -#endif - -/** @brief Specifies the datatype of a MAVLink parameter. */ -#ifndef HAVE_ENUM_MAV_PARAM_TYPE -#define HAVE_ENUM_MAV_PARAM_TYPE -typedef enum MAV_PARAM_TYPE -{ - MAV_PARAM_TYPE_UINT8=1, /* 8-bit unsigned integer | */ - MAV_PARAM_TYPE_INT8=2, /* 8-bit signed integer | */ - MAV_PARAM_TYPE_UINT16=3, /* 16-bit unsigned integer | */ - MAV_PARAM_TYPE_INT16=4, /* 16-bit signed integer | */ - MAV_PARAM_TYPE_UINT32=5, /* 32-bit unsigned integer | */ - MAV_PARAM_TYPE_INT32=6, /* 32-bit signed integer | */ - MAV_PARAM_TYPE_UINT64=7, /* 64-bit unsigned integer | */ - MAV_PARAM_TYPE_INT64=8, /* 64-bit signed integer | */ - MAV_PARAM_TYPE_REAL32=9, /* 32-bit floating-point | */ - MAV_PARAM_TYPE_REAL64=10, /* 64-bit floating-point | */ - MAV_PARAM_TYPE_ENUM_END=11, /* | */ -} MAV_PARAM_TYPE; -#endif - -/** @brief result from a mavlink command */ -#ifndef HAVE_ENUM_MAV_RESULT -#define HAVE_ENUM_MAV_RESULT -typedef enum MAV_RESULT -{ - MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ - MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ - MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */ - MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ - MAV_RESULT_FAILED=4, /* Command executed, but failed | */ - MAV_RESULT_ENUM_END=5, /* | */ -} MAV_RESULT; -#endif - -/** @brief result in a mavlink mission ack */ -#ifndef HAVE_ENUM_MAV_MISSION_RESULT -#define HAVE_ENUM_MAV_MISSION_RESULT -typedef enum MAV_MISSION_RESULT -{ - MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ - MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ - MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */ - MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */ - MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */ - MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */ - MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */ - MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */ - MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */ - MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */ - MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */ - MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */ - MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */ - MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ - MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ - MAV_MISSION_RESULT_ENUM_END=15, /* | */ -} MAV_MISSION_RESULT; -#endif - -/** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ -#ifndef HAVE_ENUM_MAV_SEVERITY -#define HAVE_ENUM_MAV_SEVERITY -typedef enum MAV_SEVERITY -{ - MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */ - MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ - MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */ - MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */ - MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */ - MAV_SEVERITY_NOTICE=5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */ - MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ - MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ - MAV_SEVERITY_ENUM_END=8, /* | */ -} MAV_SEVERITY; -#endif - -/** @brief Power supply status flags (bitmask) */ -#ifndef HAVE_ENUM_MAV_POWER_STATUS -#define HAVE_ENUM_MAV_POWER_STATUS -typedef enum MAV_POWER_STATUS -{ - MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */ - MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */ - MAV_POWER_STATUS_USB_CONNECTED=4, /* USB power is connected | */ - MAV_POWER_STATUS_PERIPH_OVERCURRENT=8, /* peripheral supply is in over-current state | */ - MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */ - MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */ - MAV_POWER_STATUS_ENUM_END=33, /* | */ -} MAV_POWER_STATUS; -#endif - -/** @brief SERIAL_CONTROL device types */ -#ifndef HAVE_ENUM_SERIAL_CONTROL_DEV -#define HAVE_ENUM_SERIAL_CONTROL_DEV -typedef enum SERIAL_CONTROL_DEV -{ - SERIAL_CONTROL_DEV_TELEM1=0, /* First telemetry port | */ - SERIAL_CONTROL_DEV_TELEM2=1, /* Second telemetry port | */ - SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */ - SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */ - SERIAL_CONTROL_DEV_SHELL=10, /* system shell | */ - SERIAL_CONTROL_DEV_ENUM_END=11, /* | */ -} SERIAL_CONTROL_DEV; -#endif - -/** @brief SERIAL_CONTROL flags (bitmask) */ -#ifndef HAVE_ENUM_SERIAL_CONTROL_FLAG -#define HAVE_ENUM_SERIAL_CONTROL_FLAG -typedef enum SERIAL_CONTROL_FLAG -{ - SERIAL_CONTROL_FLAG_REPLY=1, /* Set if this is a reply | */ - SERIAL_CONTROL_FLAG_RESPOND=2, /* Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | */ - SERIAL_CONTROL_FLAG_EXCLUSIVE=4, /* Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set | */ - SERIAL_CONTROL_FLAG_BLOCKING=8, /* Block on writes to the serial port | */ - SERIAL_CONTROL_FLAG_MULTI=16, /* Send multiple replies until port is drained | */ - SERIAL_CONTROL_FLAG_ENUM_END=17, /* | */ -} SERIAL_CONTROL_FLAG; -#endif - -/** @brief Enumeration of distance sensor types */ -#ifndef HAVE_ENUM_MAV_DISTANCE_SENSOR -#define HAVE_ENUM_MAV_DISTANCE_SENSOR -typedef enum MAV_DISTANCE_SENSOR -{ - MAV_DISTANCE_SENSOR_LASER=0, /* Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units | */ - MAV_DISTANCE_SENSOR_ULTRASOUND=1, /* Ultrasound rangefinder, e.g. MaxBotix units | */ - MAV_DISTANCE_SENSOR_INFRARED=2, /* Infrared rangefinder, e.g. Sharp units | */ - MAV_DISTANCE_SENSOR_ENUM_END=3, /* | */ -} MAV_DISTANCE_SENSOR; -#endif - -/** @brief Enumeration of sensor orientation, according to its rotations */ -#ifndef HAVE_ENUM_MAV_SENSOR_ORIENTATION -#define HAVE_ENUM_MAV_SENSOR_ORIENTATION -typedef enum MAV_SENSOR_ORIENTATION -{ - MAV_SENSOR_ROTATION_NONE=0, /* Roll: 0, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_YAW_45=1, /* Roll: 0, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_YAW_90=2, /* Roll: 0, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_YAW_135=3, /* Roll: 0, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_YAW_180=4, /* Roll: 0, Pitch: 0, Yaw: 180 | */ - MAV_SENSOR_ROTATION_YAW_225=5, /* Roll: 0, Pitch: 0, Yaw: 225 | */ - MAV_SENSOR_ROTATION_YAW_270=6, /* Roll: 0, Pitch: 0, Yaw: 270 | */ - MAV_SENSOR_ROTATION_YAW_315=7, /* Roll: 0, Pitch: 0, Yaw: 315 | */ - MAV_SENSOR_ROTATION_ROLL_180=8, /* Roll: 180, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_45=9, /* Roll: 180, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_90=10, /* Roll: 180, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_135=11, /* Roll: 180, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_PITCH_180=12, /* Roll: 0, Pitch: 180, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_225=13, /* Roll: 180, Pitch: 0, Yaw: 225 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_270=14, /* Roll: 180, Pitch: 0, Yaw: 270 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_315=15, /* Roll: 180, Pitch: 0, Yaw: 315 | */ - MAV_SENSOR_ROTATION_ROLL_90=16, /* Roll: 90, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_45=17, /* Roll: 90, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_90=18, /* Roll: 90, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_135=19, /* Roll: 90, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_ROLL_270=20, /* Roll: 270, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_YAW_45=21, /* Roll: 270, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_ROLL_270_YAW_90=22, /* Roll: 270, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_270_YAW_135=23, /* Roll: 270, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_PITCH_90=24, /* Roll: 0, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_PITCH_270=25, /* Roll: 0, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_PITCH_180_YAW_90=26, /* Roll: 0, Pitch: 180, Yaw: 90 | */ - MAV_SENSOR_ROTATION_PITCH_180_YAW_270=27, /* Roll: 0, Pitch: 180, Yaw: 270 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_90=28, /* Roll: 90, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_PITCH_90=29, /* Roll: 180, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_PITCH_90=30, /* Roll: 270, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_180=31, /* Roll: 90, Pitch: 180, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_PITCH_180=32, /* Roll: 270, Pitch: 180, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_270=33, /* Roll: 90, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_PITCH_270=34, /* Roll: 180, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_PITCH_270=35, /* Roll: 270, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90=36, /* Roll: 90, Pitch: 180, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_270=37, /* Roll: 90, Pitch: 0, Yaw: 270 | */ - MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315=38, /* Roll: 315, Pitch: 315, Yaw: 315 | */ - MAV_SENSOR_ORIENTATION_ENUM_END=39, /* | */ -} MAV_SENSOR_ORIENTATION; -#endif - -/** @brief Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. */ -#ifndef HAVE_ENUM_MAV_PROTOCOL_CAPABILITY -#define HAVE_ENUM_MAV_PROTOCOL_CAPABILITY -typedef enum MAV_PROTOCOL_CAPABILITY -{ - MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT=1, /* Autopilot supports MISSION float message type. | */ - MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT=2, /* Autopilot supports the new param float message type. | */ - MAV_PROTOCOL_CAPABILITY_MISSION_INT=4, /* Autopilot supports MISSION_INT scaled integer message type. | */ - MAV_PROTOCOL_CAPABILITY_COMMAND_INT=8, /* Autopilot supports COMMAND_INT scaled integer message type. | */ - MAV_PROTOCOL_CAPABILITY_PARAM_UNION=16, /* Autopilot supports the new param union message type. | */ - MAV_PROTOCOL_CAPABILITY_FTP=32, /* Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. | */ - MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET=64, /* Autopilot supports commanding attitude offboard. | */ - MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED=128, /* Autopilot supports commanding position and velocity targets in local NED frame. | */ - MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT=256, /* Autopilot supports commanding position and velocity targets in global scaled integers. | */ - MAV_PROTOCOL_CAPABILITY_TERRAIN=512, /* Autopilot supports terrain protocol / data handling. | */ - MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET=1024, /* Autopilot supports direct actuator control. | */ - MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION=2048, /* Autopilot supports the flight termination command. | */ - MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION=4096, /* Autopilot supports onboard compass calibration. | */ - MAV_PROTOCOL_CAPABILITY_MAVLINK2=8192, /* Autopilot supports mavlink version 2. | */ - MAV_PROTOCOL_CAPABILITY_MISSION_FENCE=16384, /* Autopilot supports mission fence protocol. | */ - MAV_PROTOCOL_CAPABILITY_MISSION_RALLY=32768, /* Autopilot supports mission rally point protocol. | */ - MAV_PROTOCOL_CAPABILITY_ENUM_END=32769, /* | */ -} MAV_PROTOCOL_CAPABILITY; -#endif - -/** @brief Type of mission items being requested/sent in mission protocol. */ -#ifndef HAVE_ENUM_MAV_MISSION_TYPE -#define HAVE_ENUM_MAV_MISSION_TYPE -typedef enum MAV_MISSION_TYPE -{ - MAV_MISSION_TYPE_MISSION=0, /* Items are mission commands for main mission. | */ - MAV_MISSION_TYPE_FENCE=1, /* Specifies GeoFence area(s). Items are MAV_CMD_FENCE_ GeoFence items. | */ - MAV_MISSION_TYPE_RALLY=2, /* Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_RALLY_POINT rally point items. | */ - MAV_MISSION_TYPE_ALL=255, /* Only used in MISSION_CLEAR_ALL to clear all mission types. | */ - MAV_MISSION_TYPE_ENUM_END=256, /* | */ -} MAV_MISSION_TYPE; -#endif - -/** @brief Enumeration of estimator types */ -#ifndef HAVE_ENUM_MAV_ESTIMATOR_TYPE -#define HAVE_ENUM_MAV_ESTIMATOR_TYPE -typedef enum MAV_ESTIMATOR_TYPE -{ - MAV_ESTIMATOR_TYPE_NAIVE=1, /* This is a naive estimator without any real covariance feedback. | */ - MAV_ESTIMATOR_TYPE_VISION=2, /* Computer vision based estimate. Might be up to scale. | */ - MAV_ESTIMATOR_TYPE_VIO=3, /* Visual-inertial estimate. | */ - MAV_ESTIMATOR_TYPE_GPS=4, /* Plain GPS estimate. | */ - MAV_ESTIMATOR_TYPE_GPS_INS=5, /* Estimator integrating GPS and inertial sensing. | */ - MAV_ESTIMATOR_TYPE_ENUM_END=6, /* | */ -} MAV_ESTIMATOR_TYPE; -#endif - -/** @brief Enumeration of battery types */ -#ifndef HAVE_ENUM_MAV_BATTERY_TYPE -#define HAVE_ENUM_MAV_BATTERY_TYPE -typedef enum MAV_BATTERY_TYPE -{ - MAV_BATTERY_TYPE_UNKNOWN=0, /* Not specified. | */ - MAV_BATTERY_TYPE_LIPO=1, /* Lithium polymer battery | */ - MAV_BATTERY_TYPE_LIFE=2, /* Lithium-iron-phosphate battery | */ - MAV_BATTERY_TYPE_LION=3, /* Lithium-ION battery | */ - MAV_BATTERY_TYPE_NIMH=4, /* Nickel metal hydride battery | */ - MAV_BATTERY_TYPE_ENUM_END=5, /* | */ -} MAV_BATTERY_TYPE; -#endif - -/** @brief Enumeration of battery functions */ -#ifndef HAVE_ENUM_MAV_BATTERY_FUNCTION -#define HAVE_ENUM_MAV_BATTERY_FUNCTION -typedef enum MAV_BATTERY_FUNCTION -{ - MAV_BATTERY_FUNCTION_UNKNOWN=0, /* Battery function is unknown | */ - MAV_BATTERY_FUNCTION_ALL=1, /* Battery supports all flight systems | */ - MAV_BATTERY_FUNCTION_PROPULSION=2, /* Battery for the propulsion system | */ - MAV_BATTERY_FUNCTION_AVIONICS=3, /* Avionics battery | */ - MAV_BATTERY_TYPE_PAYLOAD=4, /* Payload battery | */ - MAV_BATTERY_FUNCTION_ENUM_END=5, /* | */ -} MAV_BATTERY_FUNCTION; -#endif - -/** @brief Enumeration of VTOL states */ -#ifndef HAVE_ENUM_MAV_VTOL_STATE -#define HAVE_ENUM_MAV_VTOL_STATE -typedef enum MAV_VTOL_STATE -{ - MAV_VTOL_STATE_UNDEFINED=0, /* MAV is not configured as VTOL | */ - MAV_VTOL_STATE_TRANSITION_TO_FW=1, /* VTOL is in transition from multicopter to fixed-wing | */ - MAV_VTOL_STATE_TRANSITION_TO_MC=2, /* VTOL is in transition from fixed-wing to multicopter | */ - MAV_VTOL_STATE_MC=3, /* VTOL is in multicopter state | */ - MAV_VTOL_STATE_FW=4, /* VTOL is in fixed-wing state | */ - MAV_VTOL_STATE_ENUM_END=5, /* | */ -} MAV_VTOL_STATE; -#endif - -/** @brief Enumeration of landed detector states */ -#ifndef HAVE_ENUM_MAV_LANDED_STATE -#define HAVE_ENUM_MAV_LANDED_STATE -typedef enum MAV_LANDED_STATE -{ - MAV_LANDED_STATE_UNDEFINED=0, /* MAV landed state is unknown | */ - MAV_LANDED_STATE_ON_GROUND=1, /* MAV is landed (on ground) | */ - MAV_LANDED_STATE_IN_AIR=2, /* MAV is in air | */ - MAV_LANDED_STATE_ENUM_END=3, /* | */ -} MAV_LANDED_STATE; -#endif - -/** @brief Enumeration of the ADSB altimeter types */ -#ifndef HAVE_ENUM_ADSB_ALTITUDE_TYPE -#define HAVE_ENUM_ADSB_ALTITUDE_TYPE -typedef enum ADSB_ALTITUDE_TYPE -{ - ADSB_ALTITUDE_TYPE_PRESSURE_QNH=0, /* Altitude reported from a Baro source using QNH reference | */ - ADSB_ALTITUDE_TYPE_GEOMETRIC=1, /* Altitude reported from a GNSS source | */ - ADSB_ALTITUDE_TYPE_ENUM_END=2, /* | */ -} ADSB_ALTITUDE_TYPE; -#endif - -/** @brief ADSB classification for the type of vehicle emitting the transponder signal */ -#ifndef HAVE_ENUM_ADSB_EMITTER_TYPE -#define HAVE_ENUM_ADSB_EMITTER_TYPE -typedef enum ADSB_EMITTER_TYPE -{ - ADSB_EMITTER_TYPE_NO_INFO=0, /* | */ - ADSB_EMITTER_TYPE_LIGHT=1, /* | */ - ADSB_EMITTER_TYPE_SMALL=2, /* | */ - ADSB_EMITTER_TYPE_LARGE=3, /* | */ - ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE=4, /* | */ - ADSB_EMITTER_TYPE_HEAVY=5, /* | */ - ADSB_EMITTER_TYPE_HIGHLY_MANUV=6, /* | */ - ADSB_EMITTER_TYPE_ROTOCRAFT=7, /* | */ - ADSB_EMITTER_TYPE_UNASSIGNED=8, /* | */ - ADSB_EMITTER_TYPE_GLIDER=9, /* | */ - ADSB_EMITTER_TYPE_LIGHTER_AIR=10, /* | */ - ADSB_EMITTER_TYPE_PARACHUTE=11, /* | */ - ADSB_EMITTER_TYPE_ULTRA_LIGHT=12, /* | */ - ADSB_EMITTER_TYPE_UNASSIGNED2=13, /* | */ - ADSB_EMITTER_TYPE_UAV=14, /* | */ - ADSB_EMITTER_TYPE_SPACE=15, /* | */ - ADSB_EMITTER_TYPE_UNASSGINED3=16, /* | */ - ADSB_EMITTER_TYPE_EMERGENCY_SURFACE=17, /* | */ - ADSB_EMITTER_TYPE_SERVICE_SURFACE=18, /* | */ - ADSB_EMITTER_TYPE_POINT_OBSTACLE=19, /* | */ - ADSB_EMITTER_TYPE_ENUM_END=20, /* | */ -} ADSB_EMITTER_TYPE; -#endif - -/** @brief These flags indicate status such as data validity of each data source. Set = data valid */ -#ifndef HAVE_ENUM_ADSB_FLAGS -#define HAVE_ENUM_ADSB_FLAGS -typedef enum ADSB_FLAGS -{ - ADSB_FLAGS_VALID_COORDS=1, /* | */ - ADSB_FLAGS_VALID_ALTITUDE=2, /* | */ - ADSB_FLAGS_VALID_HEADING=4, /* | */ - ADSB_FLAGS_VALID_VELOCITY=8, /* | */ - ADSB_FLAGS_VALID_CALLSIGN=16, /* | */ - ADSB_FLAGS_VALID_SQUAWK=32, /* | */ - ADSB_FLAGS_SIMULATED=64, /* | */ - ADSB_FLAGS_ENUM_END=65, /* | */ -} ADSB_FLAGS; -#endif - -/** @brief Bitmask of options for the MAV_CMD_DO_REPOSITION */ -#ifndef HAVE_ENUM_MAV_DO_REPOSITION_FLAGS -#define HAVE_ENUM_MAV_DO_REPOSITION_FLAGS -typedef enum MAV_DO_REPOSITION_FLAGS -{ - MAV_DO_REPOSITION_FLAGS_CHANGE_MODE=1, /* The aircraft should immediately transition into guided. This should not be set for follow me applications | */ - MAV_DO_REPOSITION_FLAGS_ENUM_END=2, /* | */ -} MAV_DO_REPOSITION_FLAGS; -#endif - -/** @brief Flags in EKF_STATUS message */ -#ifndef HAVE_ENUM_ESTIMATOR_STATUS_FLAGS -#define HAVE_ENUM_ESTIMATOR_STATUS_FLAGS -typedef enum ESTIMATOR_STATUS_FLAGS -{ - ESTIMATOR_ATTITUDE=1, /* True if the attitude estimate is good | */ - ESTIMATOR_VELOCITY_HORIZ=2, /* True if the horizontal velocity estimate is good | */ - ESTIMATOR_VELOCITY_VERT=4, /* True if the vertical velocity estimate is good | */ - ESTIMATOR_POS_HORIZ_REL=8, /* True if the horizontal position (relative) estimate is good | */ - ESTIMATOR_POS_HORIZ_ABS=16, /* True if the horizontal position (absolute) estimate is good | */ - ESTIMATOR_POS_VERT_ABS=32, /* True if the vertical position (absolute) estimate is good | */ - ESTIMATOR_POS_VERT_AGL=64, /* True if the vertical position (above ground) estimate is good | */ - ESTIMATOR_CONST_POS_MODE=128, /* True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) | */ - ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */ - ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */ - ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */ - ESTIMATOR_STATUS_FLAGS_ENUM_END=1025, /* | */ -} ESTIMATOR_STATUS_FLAGS; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE -#define HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE -typedef enum MOTOR_TEST_THROTTLE_TYPE -{ - MOTOR_TEST_THROTTLE_PERCENT=0, /* throttle as a percentage from 0 ~ 100 | */ - MOTOR_TEST_THROTTLE_PWM=1, /* throttle as an absolute PWM value (normally in range of 1000~2000) | */ - MOTOR_TEST_THROTTLE_PILOT=2, /* throttle pass-through from pilot's transmitter | */ - MOTOR_TEST_THROTTLE_TYPE_ENUM_END=3, /* | */ -} MOTOR_TEST_THROTTLE_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_GPS_INPUT_IGNORE_FLAGS -#define HAVE_ENUM_GPS_INPUT_IGNORE_FLAGS -typedef enum GPS_INPUT_IGNORE_FLAGS -{ - GPS_INPUT_IGNORE_FLAG_ALT=1, /* ignore altitude field | */ - GPS_INPUT_IGNORE_FLAG_HDOP=2, /* ignore hdop field | */ - GPS_INPUT_IGNORE_FLAG_VDOP=4, /* ignore vdop field | */ - GPS_INPUT_IGNORE_FLAG_VEL_HORIZ=8, /* ignore horizontal velocity field (vn and ve) | */ - GPS_INPUT_IGNORE_FLAG_VEL_VERT=16, /* ignore vertical velocity field (vd) | */ - GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY=32, /* ignore speed accuracy field | */ - GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY=64, /* ignore horizontal accuracy field | */ - GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY=128, /* ignore vertical accuracy field | */ - GPS_INPUT_IGNORE_FLAGS_ENUM_END=129, /* | */ -} GPS_INPUT_IGNORE_FLAGS; -#endif - -/** @brief Possible actions an aircraft can take to avoid a collision. */ -#ifndef HAVE_ENUM_MAV_COLLISION_ACTION -#define HAVE_ENUM_MAV_COLLISION_ACTION -typedef enum MAV_COLLISION_ACTION -{ - MAV_COLLISION_ACTION_NONE=0, /* Ignore any potential collisions | */ - MAV_COLLISION_ACTION_REPORT=1, /* Report potential collision | */ - MAV_COLLISION_ACTION_ASCEND_OR_DESCEND=2, /* Ascend or Descend to avoid threat | */ - MAV_COLLISION_ACTION_MOVE_HORIZONTALLY=3, /* Move horizontally to avoid threat | */ - MAV_COLLISION_ACTION_MOVE_PERPENDICULAR=4, /* Aircraft to move perpendicular to the collision's velocity vector | */ - MAV_COLLISION_ACTION_RTL=5, /* Aircraft to fly directly back to its launch point | */ - MAV_COLLISION_ACTION_HOVER=6, /* Aircraft to stop in place | */ - MAV_COLLISION_ACTION_ENUM_END=7, /* | */ -} MAV_COLLISION_ACTION; -#endif - -/** @brief Aircraft-rated danger from this threat. */ -#ifndef HAVE_ENUM_MAV_COLLISION_THREAT_LEVEL -#define HAVE_ENUM_MAV_COLLISION_THREAT_LEVEL -typedef enum MAV_COLLISION_THREAT_LEVEL -{ - MAV_COLLISION_THREAT_LEVEL_NONE=0, /* Not a threat | */ - MAV_COLLISION_THREAT_LEVEL_LOW=1, /* Craft is mildly concerned about this threat | */ - MAV_COLLISION_THREAT_LEVEL_HIGH=2, /* Craft is panicing, and may take actions to avoid threat | */ - MAV_COLLISION_THREAT_LEVEL_ENUM_END=3, /* | */ -} MAV_COLLISION_THREAT_LEVEL; -#endif - -/** @brief Source of information about this collision. */ -#ifndef HAVE_ENUM_MAV_COLLISION_SRC -#define HAVE_ENUM_MAV_COLLISION_SRC -typedef enum MAV_COLLISION_SRC -{ - MAV_COLLISION_SRC_ADSB=0, /* ID field references ADSB_VEHICLE packets | */ - MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT=1, /* ID field references MAVLink SRC ID | */ - MAV_COLLISION_SRC_ENUM_END=2, /* | */ -} MAV_COLLISION_SRC; -#endif - -/** @brief Type of GPS fix */ -#ifndef HAVE_ENUM_GPS_FIX_TYPE -#define HAVE_ENUM_GPS_FIX_TYPE -typedef enum GPS_FIX_TYPE -{ - GPS_FIX_TYPE_NO_GPS=0, /* No GPS connected | */ - GPS_FIX_TYPE_NO_FIX=1, /* No position information, GPS is connected | */ - GPS_FIX_TYPE_2D_FIX=2, /* 2D position | */ - GPS_FIX_TYPE_3D_FIX=3, /* 3D position | */ - GPS_FIX_TYPE_DGPS=4, /* DGPS/SBAS aided 3D position | */ - GPS_FIX_TYPE_RTK_FLOAT=5, /* RTK float, 3D position | */ - GPS_FIX_TYPE_RTK_FIXED=6, /* RTK Fixed, 3D position | */ - GPS_FIX_TYPE_STATIC=7, /* Static fixed, typically used for base stations | */ - GPS_FIX_TYPE_ENUM_END=8, /* | */ -} GPS_FIX_TYPE; -#endif - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_heartbeat.h" -#include "./mavlink_msg_sys_status.h" -#include "./mavlink_msg_system_time.h" -#include "./mavlink_msg_ping.h" -#include "./mavlink_msg_change_operator_control.h" -#include "./mavlink_msg_change_operator_control_ack.h" -#include "./mavlink_msg_auth_key.h" -#include "./mavlink_msg_set_mode.h" -#include "./mavlink_msg_param_request_read.h" -#include "./mavlink_msg_param_request_list.h" -#include "./mavlink_msg_param_value.h" -#include "./mavlink_msg_param_set.h" -#include "./mavlink_msg_gps_raw_int.h" -#include "./mavlink_msg_gps_status.h" -#include "./mavlink_msg_scaled_imu.h" -#include "./mavlink_msg_raw_imu.h" -#include "./mavlink_msg_raw_pressure.h" -#include "./mavlink_msg_scaled_pressure.h" -#include "./mavlink_msg_attitude.h" -#include "./mavlink_msg_attitude_quaternion.h" -#include "./mavlink_msg_local_position_ned.h" -#include "./mavlink_msg_global_position_int.h" -#include "./mavlink_msg_rc_channels_scaled.h" -#include "./mavlink_msg_rc_channels_raw.h" -#include "./mavlink_msg_servo_output_raw.h" -#include "./mavlink_msg_mission_request_partial_list.h" -#include "./mavlink_msg_mission_write_partial_list.h" -#include "./mavlink_msg_mission_item.h" -#include "./mavlink_msg_mission_request.h" -#include "./mavlink_msg_mission_set_current.h" -#include "./mavlink_msg_mission_current.h" -#include "./mavlink_msg_mission_request_list.h" -#include "./mavlink_msg_mission_count.h" -#include "./mavlink_msg_mission_clear_all.h" -#include "./mavlink_msg_mission_item_reached.h" -#include "./mavlink_msg_mission_ack.h" -#include "./mavlink_msg_set_gps_global_origin.h" -#include "./mavlink_msg_gps_global_origin.h" -#include "./mavlink_msg_param_map_rc.h" -#include "./mavlink_msg_mission_request_int.h" -#include "./mavlink_msg_safety_set_allowed_area.h" -#include "./mavlink_msg_safety_allowed_area.h" -#include "./mavlink_msg_attitude_quaternion_cov.h" -#include "./mavlink_msg_nav_controller_output.h" -#include "./mavlink_msg_global_position_int_cov.h" -#include "./mavlink_msg_local_position_ned_cov.h" -#include "./mavlink_msg_rc_channels.h" -#include "./mavlink_msg_request_data_stream.h" -#include "./mavlink_msg_data_stream.h" -#include "./mavlink_msg_manual_control.h" -#include "./mavlink_msg_rc_channels_override.h" -#include "./mavlink_msg_mission_item_int.h" -#include "./mavlink_msg_vfr_hud.h" -#include "./mavlink_msg_command_int.h" -#include "./mavlink_msg_command_long.h" -#include "./mavlink_msg_command_ack.h" -#include "./mavlink_msg_manual_setpoint.h" -#include "./mavlink_msg_set_attitude_target.h" -#include "./mavlink_msg_attitude_target.h" -#include "./mavlink_msg_set_position_target_local_ned.h" -#include "./mavlink_msg_position_target_local_ned.h" -#include "./mavlink_msg_set_position_target_global_int.h" -#include "./mavlink_msg_position_target_global_int.h" -#include "./mavlink_msg_local_position_ned_system_global_offset.h" -#include "./mavlink_msg_hil_state.h" -#include "./mavlink_msg_hil_controls.h" -#include "./mavlink_msg_hil_rc_inputs_raw.h" -#include "./mavlink_msg_hil_actuator_controls.h" -#include "./mavlink_msg_optical_flow.h" -#include "./mavlink_msg_global_vision_position_estimate.h" -#include "./mavlink_msg_vision_position_estimate.h" -#include "./mavlink_msg_vision_speed_estimate.h" -#include "./mavlink_msg_vicon_position_estimate.h" -#include "./mavlink_msg_highres_imu.h" -#include "./mavlink_msg_optical_flow_rad.h" -#include "./mavlink_msg_hil_sensor.h" -#include "./mavlink_msg_sim_state.h" -#include "./mavlink_msg_radio_status.h" -#include "./mavlink_msg_file_transfer_protocol.h" -#include "./mavlink_msg_timesync.h" -#include "./mavlink_msg_camera_trigger.h" -#include "./mavlink_msg_hil_gps.h" -#include "./mavlink_msg_hil_optical_flow.h" -#include "./mavlink_msg_hil_state_quaternion.h" -#include "./mavlink_msg_scaled_imu2.h" -#include "./mavlink_msg_log_request_list.h" -#include "./mavlink_msg_log_entry.h" -#include "./mavlink_msg_log_request_data.h" -#include "./mavlink_msg_log_data.h" -#include "./mavlink_msg_log_erase.h" -#include "./mavlink_msg_log_request_end.h" -#include "./mavlink_msg_gps_inject_data.h" -#include "./mavlink_msg_gps2_raw.h" -#include "./mavlink_msg_power_status.h" -#include "./mavlink_msg_serial_control.h" -#include "./mavlink_msg_gps_rtk.h" -#include "./mavlink_msg_gps2_rtk.h" -#include "./mavlink_msg_scaled_imu3.h" -#include "./mavlink_msg_data_transmission_handshake.h" -#include "./mavlink_msg_encapsulated_data.h" -#include "./mavlink_msg_distance_sensor.h" -#include "./mavlink_msg_terrain_request.h" -#include "./mavlink_msg_terrain_data.h" -#include "./mavlink_msg_terrain_check.h" -#include "./mavlink_msg_terrain_report.h" -#include "./mavlink_msg_scaled_pressure2.h" -#include "./mavlink_msg_att_pos_mocap.h" -#include "./mavlink_msg_set_actuator_control_target.h" -#include "./mavlink_msg_actuator_control_target.h" -#include "./mavlink_msg_altitude.h" -#include "./mavlink_msg_resource_request.h" -#include "./mavlink_msg_scaled_pressure3.h" -#include "./mavlink_msg_follow_target.h" -#include "./mavlink_msg_control_system_state.h" -#include "./mavlink_msg_battery_status.h" -#include "./mavlink_msg_autopilot_version.h" -#include "./mavlink_msg_landing_target.h" -#include "./mavlink_msg_estimator_status.h" -#include "./mavlink_msg_wind_cov.h" -#include "./mavlink_msg_gps_input.h" -#include "./mavlink_msg_gps_rtcm_data.h" -#include "./mavlink_msg_high_latency.h" -#include "./mavlink_msg_vibration.h" -#include "./mavlink_msg_home_position.h" -#include "./mavlink_msg_set_home_position.h" -#include "./mavlink_msg_message_interval.h" -#include "./mavlink_msg_extended_sys_state.h" -#include "./mavlink_msg_adsb_vehicle.h" -#include "./mavlink_msg_collision.h" -#include "./mavlink_msg_v2_extension.h" -#include "./mavlink_msg_memory_vect.h" -#include "./mavlink_msg_debug_vect.h" -#include "./mavlink_msg_named_value_float.h" -#include "./mavlink_msg_named_value_int.h" -#include "./mavlink_msg_statustext.h" -#include "./mavlink_msg_debug.h" -#include "./mavlink_msg_setup_signing.h" -#include "./mavlink_msg_button_change.h" -#include "./mavlink_msg_play_tune.h" -#include "./mavlink_msg_camera_information.h" -#include "./mavlink_msg_camera_settings.h" -#include "./mavlink_msg_storage_information.h" -#include "./mavlink_msg_camera_capture_status.h" -#include "./mavlink_msg_camera_image_captured.h" -#include "./mavlink_msg_flight_information.h" -#include "./mavlink_msg_mount_orientation.h" -#include "./mavlink_msg_logging_data.h" -#include "./mavlink_msg_logging_data_acked.h" -#include "./mavlink_msg_logging_ack.h" - -// base include - - -#undef MAVLINK_THIS_XML_IDX -#define MAVLINK_THIS_XML_IDX 1 - -#if MAVLINK_THIS_XML_IDX == MAVLINK_PRIMARY_XML_IDX -# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, MAVLINK_MESSAGE_INFO_GPS_INPUT, MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA, MAVLINK_MESSAGE_INFO_HIGH_LATENCY, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, MAVLINK_MESSAGE_INFO_COLLISION, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_SETUP_SIGNING, MAVLINK_MESSAGE_INFO_BUTTON_CHANGE, MAVLINK_MESSAGE_INFO_PLAY_TUNE, MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS, MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED, MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION, MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION, MAVLINK_MESSAGE_INFO_LOGGING_DATA, MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED, MAVLINK_MESSAGE_INFO_LOGGING_ACK} -# if MAVLINK_COMMAND_24BIT -# include "../mavlink_get_info.h" -# endif -#endif - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // MAVLINK_COMMON_H diff --git a/include/mavlink/v2.0/common/mavlink.h b/include/mavlink/v2.0/common/mavlink.h deleted file mode 100644 index 5f59582..0000000 --- a/include/mavlink/v2.0/common/mavlink.h +++ /dev/null @@ -1,34 +0,0 @@ -/** @file - * @brief MAVLink comm protocol built from common.xml - * @see http://mavlink.org - */ -#pragma once -#ifndef MAVLINK_H -#define MAVLINK_H - -#define MAVLINK_PRIMARY_XML_IDX 1 - -#ifndef MAVLINK_STX -#define MAVLINK_STX 253 -#endif - -#ifndef MAVLINK_ENDIAN -#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN -#endif - -#ifndef MAVLINK_ALIGNED_FIELDS -#define MAVLINK_ALIGNED_FIELDS 1 -#endif - -#ifndef MAVLINK_CRC_EXTRA -#define MAVLINK_CRC_EXTRA 1 -#endif - -#ifndef MAVLINK_COMMAND_24BIT -#define MAVLINK_COMMAND_24BIT 1 -#endif - -#include "version.h" -#include "common.h" - -#endif // MAVLINK_H diff --git a/include/mavlink/v2.0/common/mavlink_msg_actuator_control_target.h b/include/mavlink/v2.0/common/mavlink_msg_actuator_control_target.h deleted file mode 100644 index 2d1ebc0..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_actuator_control_target.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE ACTUATOR_CONTROL_TARGET PACKING - -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET 140 - -MAVPACKED( -typedef struct __mavlink_actuator_control_target_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ - uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ -}) mavlink_actuator_control_target_t; - -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41 -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN 41 -#define MAVLINK_MSG_ID_140_LEN 41 -#define MAVLINK_MSG_ID_140_MIN_LEN 41 - -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC 181 -#define MAVLINK_MSG_ID_140_CRC 181 - -#define MAVLINK_MSG_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \ - 140, \ - "ACTUATOR_CONTROL_TARGET", \ - 3, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \ - "ACTUATOR_CONTROL_TARGET", \ - 3, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ - } \ -} -#endif - -/** - * @brief Pack a actuator_control_target 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 (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t group_mlx, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Pack a actuator_control_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t group_mlx,const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Encode a actuator_control_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) -{ - return mavlink_msg_actuator_control_target_pack(system_id, component_id, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); -} - -/** - * @brief Encode a actuator_control_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) -{ - return mavlink_msg_actuator_control_target_pack_chan(system_id, component_id, chan, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); -} - -/** - * @brief Send a actuator_control_target message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -/** - * @brief Send a actuator_control_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_actuator_control_target_send_struct(mavlink_channel_t chan, const mavlink_actuator_control_target_t* actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_actuator_control_target_send(chan, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)actuator_control_target, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_actuator_control_target_t *packet = (mavlink_actuator_control_target_t *)msgbuf; - packet->time_usec = time_usec; - packet->group_mlx = group_mlx; - mav_array_memcpy(packet->controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ACTUATOR_CONTROL_TARGET UNPACKING - - -/** - * @brief Get field time_usec from actuator_control_target message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field group_mlx from actuator_control_target message - * - * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - */ -static inline uint8_t mavlink_msg_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field controls from actuator_control_target message - * - * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -static inline uint16_t mavlink_msg_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) -{ - return _MAV_RETURN_float_array(msg, controls, 8, 8); -} - -/** - * @brief Decode a actuator_control_target message into a struct - * - * @param msg The message to decode - * @param actuator_control_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_actuator_control_target_t* actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - actuator_control_target->time_usec = mavlink_msg_actuator_control_target_get_time_usec(msg); - mavlink_msg_actuator_control_target_get_controls(msg, actuator_control_target->controls); - actuator_control_target->group_mlx = mavlink_msg_actuator_control_target_get_group_mlx(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN? msg->len : MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN; - memset(actuator_control_target, 0, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); - memcpy(actuator_control_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_adsb_vehicle.h b/include/mavlink/v2.0/common/mavlink_msg_adsb_vehicle.h deleted file mode 100644 index d395be5..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_adsb_vehicle.h +++ /dev/null @@ -1,505 +0,0 @@ -#pragma once -// MESSAGE ADSB_VEHICLE PACKING - -#define MAVLINK_MSG_ID_ADSB_VEHICLE 246 - -MAVPACKED( -typedef struct __mavlink_adsb_vehicle_t { - uint32_t ICAO_address; /*< ICAO address*/ - int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ - int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ - int32_t altitude; /*< Altitude(ASL) in millimeters*/ - uint16_t heading; /*< Course over ground in centidegrees*/ - uint16_t hor_velocity; /*< The horizontal velocity in centimeters/second*/ - int16_t ver_velocity; /*< The vertical velocity in centimeters/second, positive is up*/ - uint16_t flags; /*< Flags to indicate various statuses including valid data fields*/ - uint16_t squawk; /*< Squawk code*/ - uint8_t altitude_type; /*< Type from ADSB_ALTITUDE_TYPE enum*/ - char callsign[9]; /*< The callsign, 8+null*/ - uint8_t emitter_type; /*< Type from ADSB_EMITTER_TYPE enum*/ - uint8_t tslc; /*< Time since last communication in seconds*/ -}) mavlink_adsb_vehicle_t; - -#define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN 38 -#define MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN 38 -#define MAVLINK_MSG_ID_246_LEN 38 -#define MAVLINK_MSG_ID_246_MIN_LEN 38 - -#define MAVLINK_MSG_ID_ADSB_VEHICLE_CRC 184 -#define MAVLINK_MSG_ID_246_CRC 184 - -#define MAVLINK_MSG_ADSB_VEHICLE_FIELD_CALLSIGN_LEN 9 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE { \ - 246, \ - "ADSB_VEHICLE", \ - 13, \ - { { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \ - { "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \ - { "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ - { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ - { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ - { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \ - { "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \ - { "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE { \ - "ADSB_VEHICLE", \ - 13, \ - { { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \ - { "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \ - { "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ - { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ - { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ - { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \ - { "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \ - { "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \ - } \ -} -#endif - -/** - * @brief Pack a adsb_vehicle 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 ICAO_address ICAO address - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum - * @param altitude Altitude(ASL) in millimeters - * @param heading Course over ground in centidegrees - * @param hor_velocity The horizontal velocity in centimeters/second - * @param ver_velocity The vertical velocity in centimeters/second, positive is up - * @param callsign The callsign, 8+null - * @param emitter_type Type from ADSB_EMITTER_TYPE enum - * @param tslc Time since last communication in seconds - * @param flags Flags to indicate various statuses including valid data fields - * @param squawk Squawk code - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_adsb_vehicle_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#else - mavlink_adsb_vehicle_t packet; - packet.ICAO_address = ICAO_address; - packet.lat = lat; - packet.lon = lon; - packet.altitude = altitude; - packet.heading = heading; - packet.hor_velocity = hor_velocity; - packet.ver_velocity = ver_velocity; - packet.flags = flags; - packet.squawk = squawk; - packet.altitude_type = altitude_type; - packet.emitter_type = emitter_type; - packet.tslc = tslc; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -} - -/** - * @brief Pack a adsb_vehicle message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ICAO_address ICAO address - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum - * @param altitude Altitude(ASL) in millimeters - * @param heading Course over ground in centidegrees - * @param hor_velocity The horizontal velocity in centimeters/second - * @param ver_velocity The vertical velocity in centimeters/second, positive is up - * @param callsign The callsign, 8+null - * @param emitter_type Type from ADSB_EMITTER_TYPE enum - * @param tslc Time since last communication in seconds - * @param flags Flags to indicate various statuses including valid data fields - * @param squawk Squawk code - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_adsb_vehicle_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t ICAO_address,int32_t lat,int32_t lon,uint8_t altitude_type,int32_t altitude,uint16_t heading,uint16_t hor_velocity,int16_t ver_velocity,const char *callsign,uint8_t emitter_type,uint8_t tslc,uint16_t flags,uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#else - mavlink_adsb_vehicle_t packet; - packet.ICAO_address = ICAO_address; - packet.lat = lat; - packet.lon = lon; - packet.altitude = altitude; - packet.heading = heading; - packet.hor_velocity = hor_velocity; - packet.ver_velocity = ver_velocity; - packet.flags = flags; - packet.squawk = squawk; - packet.altitude_type = altitude_type; - packet.emitter_type = emitter_type; - packet.tslc = tslc; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -} - -/** - * @brief Encode a adsb_vehicle struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param adsb_vehicle C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_adsb_vehicle_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle) -{ - return mavlink_msg_adsb_vehicle_pack(system_id, component_id, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); -} - -/** - * @brief Encode a adsb_vehicle struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param adsb_vehicle C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_adsb_vehicle_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle) -{ - return mavlink_msg_adsb_vehicle_pack_chan(system_id, component_id, chan, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); -} - -/** - * @brief Send a adsb_vehicle message - * @param chan MAVLink channel to send the message - * - * @param ICAO_address ICAO address - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum - * @param altitude Altitude(ASL) in millimeters - * @param heading Course over ground in centidegrees - * @param hor_velocity The horizontal velocity in centimeters/second - * @param ver_velocity The vertical velocity in centimeters/second, positive is up - * @param callsign The callsign, 8+null - * @param emitter_type Type from ADSB_EMITTER_TYPE enum - * @param tslc Time since last communication in seconds - * @param flags Flags to indicate various statuses including valid data fields - * @param squawk Squawk code - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_adsb_vehicle_send(mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#else - mavlink_adsb_vehicle_t packet; - packet.ICAO_address = ICAO_address; - packet.lat = lat; - packet.lon = lon; - packet.altitude = altitude; - packet.heading = heading; - packet.hor_velocity = hor_velocity; - packet.ver_velocity = ver_velocity; - packet.flags = flags; - packet.squawk = squawk; - packet.altitude_type = altitude_type; - packet.emitter_type = emitter_type; - packet.tslc = tslc; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)&packet, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#endif -} - -/** - * @brief Send a adsb_vehicle message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_adsb_vehicle_send_struct(mavlink_channel_t chan, const mavlink_adsb_vehicle_t* adsb_vehicle) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_adsb_vehicle_send(chan, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)adsb_vehicle, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ADSB_VEHICLE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_adsb_vehicle_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#else - mavlink_adsb_vehicle_t *packet = (mavlink_adsb_vehicle_t *)msgbuf; - packet->ICAO_address = ICAO_address; - packet->lat = lat; - packet->lon = lon; - packet->altitude = altitude; - packet->heading = heading; - packet->hor_velocity = hor_velocity; - packet->ver_velocity = ver_velocity; - packet->flags = flags; - packet->squawk = squawk; - packet->altitude_type = altitude_type; - packet->emitter_type = emitter_type; - packet->tslc = tslc; - mav_array_memcpy(packet->callsign, callsign, sizeof(char)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)packet, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ADSB_VEHICLE UNPACKING - - -/** - * @brief Get field ICAO_address from adsb_vehicle message - * - * @return ICAO address - */ -static inline uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field lat from adsb_vehicle message - * - * @return Latitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_adsb_vehicle_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon from adsb_vehicle message - * - * @return Longitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_adsb_vehicle_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field altitude_type from adsb_vehicle message - * - * @return Type from ADSB_ALTITUDE_TYPE enum - */ -static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field altitude from adsb_vehicle message - * - * @return Altitude(ASL) in millimeters - */ -static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field heading from adsb_vehicle message - * - * @return Course over ground in centidegrees - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field hor_velocity from adsb_vehicle message - * - * @return The horizontal velocity in centimeters/second - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field ver_velocity from adsb_vehicle message - * - * @return The vertical velocity in centimeters/second, positive is up - */ -static inline int16_t mavlink_msg_adsb_vehicle_get_ver_velocity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field callsign from adsb_vehicle message - * - * @return The callsign, 8+null - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_callsign(const mavlink_message_t* msg, char *callsign) -{ - return _MAV_RETURN_char_array(msg, callsign, 9, 27); -} - -/** - * @brief Get field emitter_type from adsb_vehicle message - * - * @return Type from ADSB_EMITTER_TYPE enum - */ -static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field tslc from adsb_vehicle message - * - * @return Time since last communication in seconds - */ -static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 37); -} - -/** - * @brief Get field flags from adsb_vehicle message - * - * @return Flags to indicate various statuses including valid data fields - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field squawk from adsb_vehicle message - * - * @return Squawk code - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_squawk(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Decode a adsb_vehicle message into a struct - * - * @param msg The message to decode - * @param adsb_vehicle C-struct to decode the message contents into - */ -static inline void mavlink_msg_adsb_vehicle_decode(const mavlink_message_t* msg, mavlink_adsb_vehicle_t* adsb_vehicle) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - adsb_vehicle->ICAO_address = mavlink_msg_adsb_vehicle_get_ICAO_address(msg); - adsb_vehicle->lat = mavlink_msg_adsb_vehicle_get_lat(msg); - adsb_vehicle->lon = mavlink_msg_adsb_vehicle_get_lon(msg); - adsb_vehicle->altitude = mavlink_msg_adsb_vehicle_get_altitude(msg); - adsb_vehicle->heading = mavlink_msg_adsb_vehicle_get_heading(msg); - adsb_vehicle->hor_velocity = mavlink_msg_adsb_vehicle_get_hor_velocity(msg); - adsb_vehicle->ver_velocity = mavlink_msg_adsb_vehicle_get_ver_velocity(msg); - adsb_vehicle->flags = mavlink_msg_adsb_vehicle_get_flags(msg); - adsb_vehicle->squawk = mavlink_msg_adsb_vehicle_get_squawk(msg); - adsb_vehicle->altitude_type = mavlink_msg_adsb_vehicle_get_altitude_type(msg); - mavlink_msg_adsb_vehicle_get_callsign(msg, adsb_vehicle->callsign); - adsb_vehicle->emitter_type = mavlink_msg_adsb_vehicle_get_emitter_type(msg); - adsb_vehicle->tslc = mavlink_msg_adsb_vehicle_get_tslc(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ADSB_VEHICLE_LEN? msg->len : MAVLINK_MSG_ID_ADSB_VEHICLE_LEN; - memset(adsb_vehicle, 0, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); - memcpy(adsb_vehicle, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_altitude.h b/include/mavlink/v2.0/common/mavlink_msg_altitude.h deleted file mode 100644 index d51a9e8..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_altitude.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE ALTITUDE PACKING - -#define MAVLINK_MSG_ID_ALTITUDE 141 - -MAVPACKED( -typedef struct __mavlink_altitude_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float altitude_monotonic; /*< This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.*/ - float altitude_amsl; /*< This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.*/ - float altitude_local; /*< This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.*/ - float altitude_relative; /*< This is the altitude above the home position. It resets on each change of the current home position.*/ - float altitude_terrain; /*< This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.*/ - float bottom_clearance; /*< This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.*/ -}) mavlink_altitude_t; - -#define MAVLINK_MSG_ID_ALTITUDE_LEN 32 -#define MAVLINK_MSG_ID_ALTITUDE_MIN_LEN 32 -#define MAVLINK_MSG_ID_141_LEN 32 -#define MAVLINK_MSG_ID_141_MIN_LEN 32 - -#define MAVLINK_MSG_ID_ALTITUDE_CRC 47 -#define MAVLINK_MSG_ID_141_CRC 47 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ALTITUDE { \ - 141, \ - "ALTITUDE", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_altitude_t, time_usec) }, \ - { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_monotonic) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_amsl) }, \ - { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_local) }, \ - { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, altitude_relative) }, \ - { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_altitude_t, altitude_terrain) }, \ - { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_altitude_t, bottom_clearance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ALTITUDE { \ - "ALTITUDE", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_altitude_t, time_usec) }, \ - { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_monotonic) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_amsl) }, \ - { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_local) }, \ - { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, altitude_relative) }, \ - { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_altitude_t, altitude_terrain) }, \ - { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_altitude_t, bottom_clearance) }, \ - } \ -} -#endif - -/** - * @brief Pack a altitude 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 (micros since boot or Unix epoch) - * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN); -#else - mavlink_altitude_t packet; - packet.time_usec = time_usec; - packet.altitude_monotonic = altitude_monotonic; - packet.altitude_amsl = altitude_amsl; - packet.altitude_local = altitude_local; - packet.altitude_relative = altitude_relative; - packet.altitude_terrain = altitude_terrain; - packet.bottom_clearance = bottom_clearance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ALTITUDE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -} - -/** - * @brief Pack a altitude message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN); -#else - mavlink_altitude_t packet; - packet.time_usec = time_usec; - packet.altitude_monotonic = altitude_monotonic; - packet.altitude_amsl = altitude_amsl; - packet.altitude_local = altitude_local; - packet.altitude_relative = altitude_relative; - packet.altitude_terrain = altitude_terrain; - packet.bottom_clearance = bottom_clearance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ALTITUDE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -} - -/** - * @brief Encode a altitude struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param altitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_altitude_t* altitude) -{ - return mavlink_msg_altitude_pack(system_id, component_id, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); -} - -/** - * @brief Encode a altitude struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param altitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_altitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_altitude_t* altitude) -{ - return mavlink_msg_altitude_pack_chan(system_id, component_id, chan, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); -} - -/** - * @brief Send a altitude message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_altitude_send(mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#else - mavlink_altitude_t packet; - packet.time_usec = time_usec; - packet.altitude_monotonic = altitude_monotonic; - packet.altitude_amsl = altitude_amsl; - packet.altitude_local = altitude_local; - packet.altitude_relative = altitude_relative; - packet.altitude_terrain = altitude_terrain; - packet.bottom_clearance = bottom_clearance; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#endif -} - -/** - * @brief Send a altitude message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_altitude_send_struct(mavlink_channel_t chan, const mavlink_altitude_t* altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_altitude_send(chan, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)altitude, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ALTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_altitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#else - mavlink_altitude_t *packet = (mavlink_altitude_t *)msgbuf; - packet->time_usec = time_usec; - packet->altitude_monotonic = altitude_monotonic; - packet->altitude_amsl = altitude_amsl; - packet->altitude_local = altitude_local; - packet->altitude_relative = altitude_relative; - packet->altitude_terrain = altitude_terrain; - packet->bottom_clearance = bottom_clearance; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ALTITUDE UNPACKING - - -/** - * @brief Get field time_usec from altitude message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_altitude_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field altitude_monotonic from altitude message - * - * @return This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - */ -static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field altitude_amsl from altitude message - * - * @return This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - */ -static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field altitude_local from altitude message - * - * @return This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - */ -static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field altitude_relative from altitude message - * - * @return This is the altitude above the home position. It resets on each change of the current home position. - */ -static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field altitude_terrain from altitude message - * - * @return This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - */ -static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field bottom_clearance from altitude message - * - * @return This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - */ -static inline float mavlink_msg_altitude_get_bottom_clearance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a altitude message into a struct - * - * @param msg The message to decode - * @param altitude C-struct to decode the message contents into - */ -static inline void mavlink_msg_altitude_decode(const mavlink_message_t* msg, mavlink_altitude_t* altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - altitude->time_usec = mavlink_msg_altitude_get_time_usec(msg); - altitude->altitude_monotonic = mavlink_msg_altitude_get_altitude_monotonic(msg); - altitude->altitude_amsl = mavlink_msg_altitude_get_altitude_amsl(msg); - altitude->altitude_local = mavlink_msg_altitude_get_altitude_local(msg); - altitude->altitude_relative = mavlink_msg_altitude_get_altitude_relative(msg); - altitude->altitude_terrain = mavlink_msg_altitude_get_altitude_terrain(msg); - altitude->bottom_clearance = mavlink_msg_altitude_get_bottom_clearance(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ALTITUDE_LEN? msg->len : MAVLINK_MSG_ID_ALTITUDE_LEN; - memset(altitude, 0, MAVLINK_MSG_ID_ALTITUDE_LEN); - memcpy(altitude, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_att_pos_mocap.h b/include/mavlink/v2.0/common/mavlink_msg_att_pos_mocap.h deleted file mode 100644 index 3c1a251..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_att_pos_mocap.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE ATT_POS_MOCAP PACKING - -#define MAVLINK_MSG_ID_ATT_POS_MOCAP 138 - -MAVPACKED( -typedef struct __mavlink_att_pos_mocap_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float x; /*< X position in meters (NED)*/ - float y; /*< Y position in meters (NED)*/ - float z; /*< Z position in meters (NED)*/ -}) mavlink_att_pos_mocap_t; - -#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36 -#define MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN 36 -#define MAVLINK_MSG_ID_138_LEN 36 -#define MAVLINK_MSG_ID_138_MIN_LEN 36 - -#define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC 109 -#define MAVLINK_MSG_ID_138_CRC 109 - -#define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \ - 138, \ - "ATT_POS_MOCAP", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \ - "ATT_POS_MOCAP", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \ - } \ -} -#endif - -/** - * @brief Pack a att_pos_mocap 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 (micros since boot or Unix epoch) - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x X position in meters (NED) - * @param y Y position in meters (NED) - * @param z Z position in meters (NED) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *q, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#else - mavlink_att_pos_mocap_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -} - -/** - * @brief Pack a att_pos_mocap message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x X position in meters (NED) - * @param y Y position in meters (NED) - * @param z Z position in meters (NED) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *q,float x,float y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#else - mavlink_att_pos_mocap_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -} - -/** - * @brief Encode a att_pos_mocap struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param att_pos_mocap C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_att_pos_mocap_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap) -{ - return mavlink_msg_att_pos_mocap_pack(system_id, component_id, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z); -} - -/** - * @brief Encode a att_pos_mocap struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param att_pos_mocap C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap) -{ - return mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, chan, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z); -} - -/** - * @brief Send a att_pos_mocap message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x X position in meters (NED) - * @param y Y position in meters (NED) - * @param z Z position in meters (NED) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#else - mavlink_att_pos_mocap_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#endif -} - -/** - * @brief Send a att_pos_mocap message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_att_pos_mocap_send_struct(mavlink_channel_t chan, const mavlink_att_pos_mocap_t* att_pos_mocap) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_att_pos_mocap_send(chan, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)att_pos_mocap, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#else - mavlink_att_pos_mocap_t *packet = (mavlink_att_pos_mocap_t *)msgbuf; - packet->time_usec = time_usec; - packet->x = x; - packet->y = y; - packet->z = z; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATT_POS_MOCAP UNPACKING - - -/** - * @brief Get field time_usec from att_pos_mocap message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field q from att_pos_mocap message - * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 8); -} - -/** - * @brief Get field x from att_pos_mocap message - * - * @return X position in meters (NED) - */ -static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field y from att_pos_mocap message - * - * @return Y position in meters (NED) - */ -static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field z from att_pos_mocap message - * - * @return Z position in meters (NED) - */ -static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Decode a att_pos_mocap message into a struct - * - * @param msg The message to decode - * @param att_pos_mocap C-struct to decode the message contents into - */ -static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t* msg, mavlink_att_pos_mocap_t* att_pos_mocap) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - att_pos_mocap->time_usec = mavlink_msg_att_pos_mocap_get_time_usec(msg); - mavlink_msg_att_pos_mocap_get_q(msg, att_pos_mocap->q); - att_pos_mocap->x = mavlink_msg_att_pos_mocap_get_x(msg); - att_pos_mocap->y = mavlink_msg_att_pos_mocap_get_y(msg); - att_pos_mocap->z = mavlink_msg_att_pos_mocap_get_z(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN? msg->len : MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN; - memset(att_pos_mocap, 0, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); - memcpy(att_pos_mocap, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_attitude.h b/include/mavlink/v2.0/common/mavlink_msg_attitude.h deleted file mode 100644 index 21472fb..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_attitude.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE PACKING - -#define MAVLINK_MSG_ID_ATTITUDE 30 - -MAVPACKED( -typedef struct __mavlink_attitude_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float roll; /*< Roll angle (rad, -pi..+pi)*/ - float pitch; /*< Pitch angle (rad, -pi..+pi)*/ - float yaw; /*< Yaw angle (rad, -pi..+pi)*/ - float rollspeed; /*< Roll angular speed (rad/s)*/ - float pitchspeed; /*< Pitch angular speed (rad/s)*/ - float yawspeed; /*< Yaw angular speed (rad/s)*/ -}) mavlink_attitude_t; - -#define MAVLINK_MSG_ID_ATTITUDE_LEN 28 -#define MAVLINK_MSG_ID_ATTITUDE_MIN_LEN 28 -#define MAVLINK_MSG_ID_30_LEN 28 -#define MAVLINK_MSG_ID_30_MIN_LEN 28 - -#define MAVLINK_MSG_ID_ATTITUDE_CRC 39 -#define MAVLINK_MSG_ID_30_CRC 39 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE { \ - 30, \ - "ATTITUDE", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE { \ - "ATTITUDE", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude 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_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - 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, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -} - -/** - * @brief Pack a attitude message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - 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, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -} - -/** - * @brief Encode a attitude struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude) -{ - return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); -} - -/** - * @brief Encode a attitude struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_t* attitude) -{ - return mavlink_msg_attitude_pack_chan(system_id, component_id, chan, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); -} - -/** - * @brief Send a attitude message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#endif -} - -/** - * @brief Send a attitude message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_send_struct(mavlink_channel_t chan, const mavlink_attitude_t* attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_send(chan, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)attitude, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE UNPACKING - - -/** - * @brief Get field time_boot_ms from attitude message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll from attitude message - * - * @return Roll angle (rad, -pi..+pi) - */ -static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch from attitude message - * - * @return Pitch angle (rad, -pi..+pi) - */ -static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from attitude message - * - * @return Yaw angle (rad, -pi..+pi) - */ -static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field rollspeed from attitude message - * - * @return Roll angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitchspeed from attitude message - * - * @return Pitch angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yawspeed from attitude message - * - * @return Yaw angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a attitude message into a struct - * - * @param msg The message to decode - * @param attitude C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg); - attitude->roll = mavlink_msg_attitude_get_roll(msg); - attitude->pitch = mavlink_msg_attitude_get_pitch(msg); - attitude->yaw = mavlink_msg_attitude_get_yaw(msg); - attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg); - attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); - attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_LEN; - memset(attitude, 0, MAVLINK_MSG_ID_ATTITUDE_LEN); - memcpy(attitude, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_attitude_quaternion.h b/include/mavlink/v2.0/common/mavlink_msg_attitude_quaternion.h deleted file mode 100644 index df8e1e9..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_attitude_quaternion.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE_QUATERNION PACKING - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 - -MAVPACKED( -typedef struct __mavlink_attitude_quaternion_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float q1; /*< Quaternion component 1, w (1 in null-rotation)*/ - float q2; /*< Quaternion component 2, x (0 in null-rotation)*/ - float q3; /*< Quaternion component 3, y (0 in null-rotation)*/ - float q4; /*< Quaternion component 4, z (0 in null-rotation)*/ - float rollspeed; /*< Roll angular speed (rad/s)*/ - float pitchspeed; /*< Pitch angular speed (rad/s)*/ - float yawspeed; /*< Yaw angular speed (rad/s)*/ -}) mavlink_attitude_quaternion_t; - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN 32 -#define MAVLINK_MSG_ID_31_LEN 32 -#define MAVLINK_MSG_ID_31_MIN_LEN 32 - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246 -#define MAVLINK_MSG_ID_31_CRC 246 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ - 31, \ - "ATTITUDE_QUATERNION", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ - { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ - "ATTITUDE_QUATERNION", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ - { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude_quaternion 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_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - - 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; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - 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, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -} - -/** - * @brief Pack a attitude_quaternion message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - - 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; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - 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, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -} - -/** - * @brief Encode a attitude_quaternion struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) -{ - return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); -} - -/** - * @brief Encode a attitude_quaternion struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) -{ - return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); -} - -/** - * @brief Send a attitude_quaternion message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - mavlink_attitude_quaternion_t packet; - packet.time_boot_ms = time_boot_ms; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#endif -} - -/** - * @brief Send a attitude_quaternion message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_quaternion_send_struct(mavlink_channel_t chan, const mavlink_attitude_quaternion_t* attitude_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_quaternion_send(chan, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)attitude_quaternion, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, q1); - _mav_put_float(buf, 8, q2); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->q1 = q1; - packet->q2 = q2; - packet->q3 = q3; - packet->q4 = q4; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE_QUATERNION UNPACKING - - -/** - * @brief Get field time_boot_ms from attitude_quaternion message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field q1 from attitude_quaternion message - * - * @return Quaternion component 1, w (1 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field q2 from attitude_quaternion message - * - * @return Quaternion component 2, x (0 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field q3 from attitude_quaternion message - * - * @return Quaternion component 3, y (0 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field q4 from attitude_quaternion message - * - * @return Quaternion component 4, z (0 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field rollspeed from attitude_quaternion message - * - * @return Roll angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitchspeed from attitude_quaternion message - * - * @return Pitch angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yawspeed from attitude_quaternion message - * - * @return Yaw angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a attitude_quaternion message into a struct - * - * @param msg The message to decode - * @param attitude_quaternion C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg); - attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg); - attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg); - attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg); - attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg); - attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg); - attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg); - attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN; - memset(attitude_quaternion, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); - memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_attitude_quaternion_cov.h b/include/mavlink/v2.0/common/mavlink_msg_attitude_quaternion_cov.h deleted file mode 100644 index adfcfa7..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_attitude_quaternion_cov.h +++ /dev/null @@ -1,331 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE_QUATERNION_COV PACKING - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61 - -MAVPACKED( -typedef struct __mavlink_attitude_quaternion_cov_t { - uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/ - float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/ - float rollspeed; /*< Roll angular speed (rad/s)*/ - float pitchspeed; /*< Pitch angular speed (rad/s)*/ - float yawspeed; /*< Yaw angular speed (rad/s)*/ - float covariance[9]; /*< Attitude covariance*/ -}) mavlink_attitude_quaternion_cov_t; - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 72 -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN 72 -#define MAVLINK_MSG_ID_61_LEN 72 -#define MAVLINK_MSG_ID_61_MIN_LEN 72 - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC 167 -#define MAVLINK_MSG_ID_61_CRC 167 - -#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN 4 -#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN 9 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \ - 61, \ - "ATTITUDE_QUATERNION_COV", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 36, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \ - "ATTITUDE_QUATERNION_COV", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 36, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude_quaternion_cov 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 since system boot or since UNIX epoch) - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @param covariance Attitude covariance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#else - mavlink_attitude_quaternion_cov_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -} - -/** - * @brief Pack a attitude_quaternion_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @param covariance Attitude covariance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *q,float rollspeed,float pitchspeed,float yawspeed,const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#else - mavlink_attitude_quaternion_cov_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -} - -/** - * @brief Encode a attitude_quaternion_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ - return mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, msg, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); -} - -/** - * @brief Encode a attitude_quaternion_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ - return mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, chan, msg, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); -} - -/** - * @brief Send a attitude_quaternion_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @param covariance Attitude covariance - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_attitude_quaternion_cov_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#else - mavlink_attitude_quaternion_cov_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#endif -} - -/** - * @brief Send a attitude_quaternion_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_quaternion_cov_send_struct(mavlink_channel_t chan, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_quaternion_cov_send(chan, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)attitude_quaternion_cov, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#else - mavlink_attitude_quaternion_cov_t *packet = (mavlink_attitude_quaternion_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE_QUATERNION_COV UNPACKING - - -/** - * @brief Get field time_usec from attitude_quaternion_cov message - * - * @return Timestamp (microseconds since system boot or since UNIX epoch) - */ -static inline uint64_t mavlink_msg_attitude_quaternion_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field q from attitude_quaternion_cov message - * - * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 8); -} - -/** - * @brief Get field rollspeed from attitude_quaternion_cov message - * - * @return Roll angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field pitchspeed from attitude_quaternion_cov message - * - * @return Pitch angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field yawspeed from attitude_quaternion_cov message - * - * @return Yaw angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field covariance from attitude_quaternion_cov message - * - * @return Attitude covariance - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 9, 36); -} - -/** - * @brief Decode a attitude_quaternion_cov message into a struct - * - * @param msg The message to decode - * @param attitude_quaternion_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_quaternion_cov_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude_quaternion_cov->time_usec = mavlink_msg_attitude_quaternion_cov_get_time_usec(msg); - mavlink_msg_attitude_quaternion_cov_get_q(msg, attitude_quaternion_cov->q); - attitude_quaternion_cov->rollspeed = mavlink_msg_attitude_quaternion_cov_get_rollspeed(msg); - attitude_quaternion_cov->pitchspeed = mavlink_msg_attitude_quaternion_cov_get_pitchspeed(msg); - attitude_quaternion_cov->yawspeed = mavlink_msg_attitude_quaternion_cov_get_yawspeed(msg); - mavlink_msg_attitude_quaternion_cov_get_covariance(msg, attitude_quaternion_cov->covariance); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN; - memset(attitude_quaternion_cov, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); - memcpy(attitude_quaternion_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_attitude_target.h b/include/mavlink/v2.0/common/mavlink_msg_attitude_target.h deleted file mode 100644 index a310920..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_attitude_target.h +++ /dev/null @@ -1,355 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE_TARGET PACKING - -#define MAVLINK_MSG_ID_ATTITUDE_TARGET 83 - -MAVPACKED( -typedef struct __mavlink_attitude_target_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float body_roll_rate; /*< Body roll rate in radians per second*/ - float body_pitch_rate; /*< Body pitch rate in radians per second*/ - float body_yaw_rate; /*< Body yaw rate in radians per second*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ - uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude*/ -}) mavlink_attitude_target_t; - -#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37 -#define MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN 37 -#define MAVLINK_MSG_ID_83_LEN 37 -#define MAVLINK_MSG_ID_83_MIN_LEN 37 - -#define MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22 -#define MAVLINK_MSG_ID_83_CRC 22 - -#define MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \ - 83, \ - "ATTITUDE_TARGET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \ - "ATTITUDE_TARGET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude_target 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_boot_ms Timestamp in milliseconds since system boot - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body pitch rate in radians per second - * @param body_yaw_rate Body yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#else - mavlink_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Pack a attitude_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body pitch rate in radians per second - * @param body_yaw_rate Body yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#else - mavlink_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Encode a attitude_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target) -{ - return mavlink_msg_attitude_target_pack(system_id, component_id, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); -} - -/** - * @brief Encode a attitude_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target) -{ - return mavlink_msg_attitude_target_pack_chan(system_id, component_id, chan, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); -} - -/** - * @brief Send a attitude_target message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body pitch rate in radians per second - * @param body_yaw_rate Body yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#else - mavlink_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#endif -} - -/** - * @brief Send a attitude_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_target_send_struct(mavlink_channel_t chan, const mavlink_attitude_target_t* attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_target_send(chan, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)attitude_target, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#else - mavlink_attitude_target_t *packet = (mavlink_attitude_target_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->body_roll_rate = body_roll_rate; - packet->body_pitch_rate = body_pitch_rate; - packet->body_yaw_rate = body_yaw_rate; - packet->thrust = thrust; - packet->type_mask = type_mask; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE_TARGET UNPACKING - - -/** - * @brief Get field time_boot_ms from attitude_target message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field type_mask from attitude_target message - * - * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - */ -static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field q from attitude_target message - * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 4); -} - -/** - * @brief Get field body_roll_rate from attitude_target message - * - * @return Body roll rate in radians per second - */ -static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field body_pitch_rate from attitude_target message - * - * @return Body pitch rate in radians per second - */ -static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field body_yaw_rate from attitude_target message - * - * @return Body yaw rate in radians per second - */ -static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field thrust from attitude_target message - * - * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - */ -static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Decode a attitude_target message into a struct - * - * @param msg The message to decode - * @param attitude_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_target_decode(const mavlink_message_t* msg, mavlink_attitude_target_t* attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude_target->time_boot_ms = mavlink_msg_attitude_target_get_time_boot_ms(msg); - mavlink_msg_attitude_target_get_q(msg, attitude_target->q); - attitude_target->body_roll_rate = mavlink_msg_attitude_target_get_body_roll_rate(msg); - attitude_target->body_pitch_rate = mavlink_msg_attitude_target_get_body_pitch_rate(msg); - attitude_target->body_yaw_rate = mavlink_msg_attitude_target_get_body_yaw_rate(msg); - attitude_target->thrust = mavlink_msg_attitude_target_get_thrust(msg); - attitude_target->type_mask = mavlink_msg_attitude_target_get_type_mask(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN; - memset(attitude_target, 0, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); - memcpy(attitude_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_auth_key.h b/include/mavlink/v2.0/common/mavlink_msg_auth_key.h deleted file mode 100644 index 2754a2a..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_auth_key.h +++ /dev/null @@ -1,213 +0,0 @@ -#pragma once -// MESSAGE AUTH_KEY PACKING - -#define MAVLINK_MSG_ID_AUTH_KEY 7 - -MAVPACKED( -typedef struct __mavlink_auth_key_t { - char key[32]; /*< key*/ -}) mavlink_auth_key_t; - -#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 -#define MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN 32 -#define MAVLINK_MSG_ID_7_LEN 32 -#define MAVLINK_MSG_ID_7_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ - 7, \ - "AUTH_KEY", \ - 1, \ - { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ - "AUTH_KEY", \ - 1, \ - { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ - } \ -} -#endif - -/** - * @brief Pack a auth_key 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 key key - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; - - _mav_put_char_array(buf, 0, key, 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, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -} - -/** - * @brief Pack a auth_key message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param key key - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; - - _mav_put_char_array(buf, 0, key, 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, 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, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -} - -/** - * @brief Encode a auth_key struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param auth_key C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) -{ - return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key); -} - -/** - * @brief Encode a auth_key struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param auth_key C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) -{ - return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key); -} - -/** - * @brief Send a auth_key message - * @param chan MAVLink channel to send the message - * - * @param key key - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#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, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#endif -} - -/** - * @brief Send a auth_key message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_auth_key_send_struct(mavlink_channel_t chan, const mavlink_auth_key_t* auth_key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_auth_key_send(chan, auth_key->key); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)auth_key, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_char_array(buf, 0, key, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#else - mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf; - - mav_array_memcpy(packet->key, key, sizeof(char)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE AUTH_KEY UNPACKING - - -/** - * @brief Get field key from auth_key message - * - * @return key - */ -static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key) -{ - return _MAV_RETURN_char_array(msg, key, 32, 0); -} - -/** - * @brief Decode a auth_key message into a struct - * - * @param msg The message to decode - * @param auth_key C-struct to decode the message contents into - */ -static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_auth_key_get_key(msg, auth_key->key); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_AUTH_KEY_LEN? msg->len : MAVLINK_MSG_ID_AUTH_KEY_LEN; - memset(auth_key, 0, MAVLINK_MSG_ID_AUTH_KEY_LEN); - memcpy(auth_key, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_autopilot_version.h b/include/mavlink/v2.0/common/mavlink_msg_autopilot_version.h deleted file mode 100644 index 68f7d83..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_autopilot_version.h +++ /dev/null @@ -1,457 +0,0 @@ -#pragma once -// MESSAGE AUTOPILOT_VERSION PACKING - -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148 - -MAVPACKED( -typedef struct __mavlink_autopilot_version_t { - uint64_t capabilities; /*< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)*/ - uint64_t uid; /*< UID if provided by hardware*/ - uint32_t flight_sw_version; /*< Firmware version number*/ - uint32_t middleware_sw_version; /*< Middleware version number*/ - uint32_t os_sw_version; /*< Operating system version number*/ - uint32_t board_version; /*< HW / board version (last 8 bytes should be silicon ID, if any)*/ - uint16_t vendor_id; /*< ID of the board vendor*/ - uint16_t product_id; /*< ID of the product*/ - uint8_t flight_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ - uint8_t middleware_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ - uint8_t os_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ -}) mavlink_autopilot_version_t; - -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60 -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN 60 -#define MAVLINK_MSG_ID_148_LEN 60 -#define MAVLINK_MSG_ID_148_MIN_LEN 60 - -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178 -#define MAVLINK_MSG_ID_148_CRC 178 - -#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN 8 -#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN 8 -#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \ - 148, \ - "AUTOPILOT_VERSION", \ - 11, \ - { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \ - { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ - { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \ - { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \ - { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \ - { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \ - { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ - { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ - { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \ - { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \ - { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \ - "AUTOPILOT_VERSION", \ - 11, \ - { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \ - { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ - { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \ - { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \ - { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \ - { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \ - { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ - { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ - { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \ - { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \ - { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \ - } \ -} -#endif - -/** - * @brief Pack a autopilot_version 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 capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#else - mavlink_autopilot_version_t packet; - packet.capabilities = capabilities; - packet.uid = uid; - packet.flight_sw_version = flight_sw_version; - packet.middleware_sw_version = middleware_sw_version; - packet.os_sw_version = os_sw_version; - packet.board_version = board_version; - packet.vendor_id = vendor_id; - packet.product_id = product_id; - mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -} - -/** - * @brief Pack a autopilot_version message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t capabilities,uint32_t flight_sw_version,uint32_t middleware_sw_version,uint32_t os_sw_version,uint32_t board_version,const uint8_t *flight_custom_version,const uint8_t *middleware_custom_version,const uint8_t *os_custom_version,uint16_t vendor_id,uint16_t product_id,uint64_t uid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#else - mavlink_autopilot_version_t packet; - packet.capabilities = capabilities; - packet.uid = uid; - packet.flight_sw_version = flight_sw_version; - packet.middleware_sw_version = middleware_sw_version; - packet.os_sw_version = os_sw_version; - packet.board_version = board_version; - packet.vendor_id = vendor_id; - packet.product_id = product_id; - mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -} - -/** - * @brief Encode a autopilot_version struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param autopilot_version C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_autopilot_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version) -{ - return mavlink_msg_autopilot_version_pack(system_id, component_id, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid); -} - -/** - * @brief Encode a autopilot_version struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param autopilot_version C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version) -{ - return mavlink_msg_autopilot_version_pack_chan(system_id, component_id, chan, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid); -} - -/** - * @brief Send a autopilot_version message - * @param chan MAVLink channel to send the message - * - * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#else - mavlink_autopilot_version_t packet; - packet.capabilities = capabilities; - packet.uid = uid; - packet.flight_sw_version = flight_sw_version; - packet.middleware_sw_version = middleware_sw_version; - packet.os_sw_version = os_sw_version; - packet.board_version = board_version; - packet.vendor_id = vendor_id; - packet.product_id = product_id; - mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#endif -} - -/** - * @brief Send a autopilot_version message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_autopilot_version_send_struct(mavlink_channel_t chan, const mavlink_autopilot_version_t* autopilot_version) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_autopilot_version_send(chan, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)autopilot_version, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#else - mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf; - packet->capabilities = capabilities; - packet->uid = uid; - packet->flight_sw_version = flight_sw_version; - packet->middleware_sw_version = middleware_sw_version; - packet->os_sw_version = os_sw_version; - packet->board_version = board_version; - packet->vendor_id = vendor_id; - packet->product_id = product_id; - mav_array_memcpy(packet->flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet->middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet->os_custom_version, os_custom_version, sizeof(uint8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE AUTOPILOT_VERSION UNPACKING - - -/** - * @brief Get field capabilities from autopilot_version message - * - * @return bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - */ -static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field flight_sw_version from autopilot_version message - * - * @return Firmware version number - */ -static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 16); -} - -/** - * @brief Get field middleware_sw_version from autopilot_version message - * - * @return Middleware version number - */ -static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field os_sw_version from autopilot_version message - * - * @return Operating system version number - */ -static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 24); -} - -/** - * @brief Get field board_version from autopilot_version message - * - * @return HW / board version (last 8 bytes should be silicon ID, if any) - */ -static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 28); -} - -/** - * @brief Get field flight_custom_version from autopilot_version message - * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - */ -static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t* msg, uint8_t *flight_custom_version) -{ - return _MAV_RETURN_uint8_t_array(msg, flight_custom_version, 8, 36); -} - -/** - * @brief Get field middleware_custom_version from autopilot_version message - * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - */ -static inline uint16_t mavlink_msg_autopilot_version_get_middleware_custom_version(const mavlink_message_t* msg, uint8_t *middleware_custom_version) -{ - return _MAV_RETURN_uint8_t_array(msg, middleware_custom_version, 8, 44); -} - -/** - * @brief Get field os_custom_version from autopilot_version message - * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - */ -static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t* msg, uint8_t *os_custom_version) -{ - return _MAV_RETURN_uint8_t_array(msg, os_custom_version, 8, 52); -} - -/** - * @brief Get field vendor_id from autopilot_version message - * - * @return ID of the board vendor - */ -static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field product_id from autopilot_version message - * - * @return ID of the product - */ -static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 34); -} - -/** - * @brief Get field uid from autopilot_version message - * - * @return UID if provided by hardware - */ -static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Decode a autopilot_version message into a struct - * - * @param msg The message to decode - * @param autopilot_version C-struct to decode the message contents into - */ -static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t* msg, mavlink_autopilot_version_t* autopilot_version) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - autopilot_version->capabilities = mavlink_msg_autopilot_version_get_capabilities(msg); - autopilot_version->uid = mavlink_msg_autopilot_version_get_uid(msg); - autopilot_version->flight_sw_version = mavlink_msg_autopilot_version_get_flight_sw_version(msg); - autopilot_version->middleware_sw_version = mavlink_msg_autopilot_version_get_middleware_sw_version(msg); - autopilot_version->os_sw_version = mavlink_msg_autopilot_version_get_os_sw_version(msg); - autopilot_version->board_version = mavlink_msg_autopilot_version_get_board_version(msg); - autopilot_version->vendor_id = mavlink_msg_autopilot_version_get_vendor_id(msg); - autopilot_version->product_id = mavlink_msg_autopilot_version_get_product_id(msg); - mavlink_msg_autopilot_version_get_flight_custom_version(msg, autopilot_version->flight_custom_version); - mavlink_msg_autopilot_version_get_middleware_custom_version(msg, autopilot_version->middleware_custom_version); - mavlink_msg_autopilot_version_get_os_custom_version(msg, autopilot_version->os_custom_version); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN? msg->len : MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN; - memset(autopilot_version, 0, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); - memcpy(autopilot_version, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_battery_status.h b/include/mavlink/v2.0/common/mavlink_msg_battery_status.h deleted file mode 100644 index d69a246..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_battery_status.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE BATTERY_STATUS PACKING - -#define MAVLINK_MSG_ID_BATTERY_STATUS 147 - -MAVPACKED( -typedef struct __mavlink_battery_status_t { - int32_t current_consumed; /*< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate*/ - int32_t energy_consumed; /*< Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate*/ - int16_t temperature; /*< Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.*/ - uint16_t voltages[10]; /*< Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.*/ - int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/ - uint8_t id; /*< Battery ID*/ - uint8_t battery_function; /*< Function of the battery*/ - uint8_t type; /*< Type (chemistry) of the battery*/ - int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery*/ -}) mavlink_battery_status_t; - -#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36 -#define MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN 36 -#define MAVLINK_MSG_ID_147_LEN 36 -#define MAVLINK_MSG_ID_147_MIN_LEN 36 - -#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154 -#define MAVLINK_MSG_ID_147_CRC 154 - -#define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ - 147, \ - "BATTERY_STATUS", \ - 9, \ - { { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ - { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \ - { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ - { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ - "BATTERY_STATUS", \ - 9, \ - { { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ - { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \ - { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ - { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \ - } \ -} -#endif - -/** - * @brief Pack a battery_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 id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.temperature = temperature; - packet.current_battery = current_battery; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.battery_remaining = battery_remaining; - mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); - 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, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -} - -/** - * @brief Pack a battery_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t id,uint8_t battery_function,uint8_t type,int16_t temperature,const uint16_t *voltages,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.temperature = temperature; - packet.current_battery = current_battery; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.battery_remaining = battery_remaining; - mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); - 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, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -} - -/** - * @brief Encode a battery_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param battery_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) -{ - return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); -} - -/** - * @brief Encode a battery_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param battery_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) -{ - return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); -} - -/** - * @brief Send a battery_status message - * @param chan MAVLink channel to send the message - * - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.temperature = temperature; - packet.current_battery = current_battery; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.battery_remaining = battery_remaining; - mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#endif -} - -/** - * @brief Send a battery_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_battery_status_send_struct(mavlink_channel_t chan, const mavlink_battery_status_t* battery_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_battery_status_send(chan, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)battery_status, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - mavlink_battery_status_t *packet = (mavlink_battery_status_t *)msgbuf; - packet->current_consumed = current_consumed; - packet->energy_consumed = energy_consumed; - packet->temperature = temperature; - packet->current_battery = current_battery; - packet->id = id; - packet->battery_function = battery_function; - packet->type = type; - packet->battery_remaining = battery_remaining; - mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE BATTERY_STATUS UNPACKING - - -/** - * @brief Get field id from battery_status message - * - * @return Battery ID - */ -static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field battery_function from battery_status message - * - * @return Function of the battery - */ -static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field type from battery_status message - * - * @return Type (chemistry) of the battery - */ -static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field temperature from battery_status message - * - * @return Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - */ -static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field voltages from battery_status message - * - * @return Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - */ -static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_message_t* msg, uint16_t *voltages) -{ - return _MAV_RETURN_uint16_t_array(msg, voltages, 10, 10); -} - -/** - * @brief Get field current_battery from battery_status message - * - * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - */ -static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 30); -} - -/** - * @brief Get field current_consumed from battery_status message - * - * @return Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - */ -static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field energy_consumed from battery_status message - * - * @return Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - */ -static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field battery_remaining from battery_status message - * - * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - */ -static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 35); -} - -/** - * @brief Decode a battery_status message into a struct - * - * @param msg The message to decode - * @param battery_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* msg, mavlink_battery_status_t* battery_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - battery_status->current_consumed = mavlink_msg_battery_status_get_current_consumed(msg); - battery_status->energy_consumed = mavlink_msg_battery_status_get_energy_consumed(msg); - battery_status->temperature = mavlink_msg_battery_status_get_temperature(msg); - mavlink_msg_battery_status_get_voltages(msg, battery_status->voltages); - battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg); - battery_status->id = mavlink_msg_battery_status_get_id(msg); - battery_status->battery_function = mavlink_msg_battery_status_get_battery_function(msg); - battery_status->type = mavlink_msg_battery_status_get_type(msg); - battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_BATTERY_STATUS_LEN? msg->len : MAVLINK_MSG_ID_BATTERY_STATUS_LEN; - memset(battery_status, 0, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); - memcpy(battery_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_button_change.h b/include/mavlink/v2.0/common/mavlink_msg_button_change.h deleted file mode 100644 index bb00971..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_button_change.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE BUTTON_CHANGE PACKING - -#define MAVLINK_MSG_ID_BUTTON_CHANGE 257 - -MAVPACKED( -typedef struct __mavlink_button_change_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - uint32_t last_change_ms; /*< Time of last change of button state*/ - uint8_t state; /*< Bitmap state of buttons*/ -}) mavlink_button_change_t; - -#define MAVLINK_MSG_ID_BUTTON_CHANGE_LEN 9 -#define MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN 9 -#define MAVLINK_MSG_ID_257_LEN 9 -#define MAVLINK_MSG_ID_257_MIN_LEN 9 - -#define MAVLINK_MSG_ID_BUTTON_CHANGE_CRC 131 -#define MAVLINK_MSG_ID_257_CRC 131 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_BUTTON_CHANGE { \ - 257, \ - "BUTTON_CHANGE", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_button_change_t, time_boot_ms) }, \ - { "last_change_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_button_change_t, last_change_ms) }, \ - { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_button_change_t, state) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_BUTTON_CHANGE { \ - "BUTTON_CHANGE", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_button_change_t, time_boot_ms) }, \ - { "last_change_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_button_change_t, last_change_ms) }, \ - { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_button_change_t, state) }, \ - } \ -} -#endif - -/** - * @brief Pack a button_change 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_boot_ms Timestamp (milliseconds since system boot) - * @param last_change_ms Time of last change of button state - * @param state Bitmap state of buttons - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_button_change_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint32_t last_change_ms, uint8_t state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BUTTON_CHANGE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, last_change_ms); - _mav_put_uint8_t(buf, 8, state); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN); -#else - mavlink_button_change_t packet; - packet.time_boot_ms = time_boot_ms; - packet.last_change_ms = last_change_ms; - packet.state = state; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_BUTTON_CHANGE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -} - -/** - * @brief Pack a button_change message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param last_change_ms Time of last change of button state - * @param state Bitmap state of buttons - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_button_change_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint32_t last_change_ms,uint8_t state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BUTTON_CHANGE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, last_change_ms); - _mav_put_uint8_t(buf, 8, state); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN); -#else - mavlink_button_change_t packet; - packet.time_boot_ms = time_boot_ms; - packet.last_change_ms = last_change_ms; - packet.state = state; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_BUTTON_CHANGE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -} - -/** - * @brief Encode a button_change struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param button_change C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_button_change_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_button_change_t* button_change) -{ - return mavlink_msg_button_change_pack(system_id, component_id, msg, button_change->time_boot_ms, button_change->last_change_ms, button_change->state); -} - -/** - * @brief Encode a button_change struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param button_change C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_button_change_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_button_change_t* button_change) -{ - return mavlink_msg_button_change_pack_chan(system_id, component_id, chan, msg, button_change->time_boot_ms, button_change->last_change_ms, button_change->state); -} - -/** - * @brief Send a button_change message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param last_change_ms Time of last change of button state - * @param state Bitmap state of buttons - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_button_change_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t last_change_ms, uint8_t state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BUTTON_CHANGE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, last_change_ms); - _mav_put_uint8_t(buf, 8, state); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, buf, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -#else - mavlink_button_change_t packet; - packet.time_boot_ms = time_boot_ms; - packet.last_change_ms = last_change_ms; - packet.state = state; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, (const char *)&packet, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -#endif -} - -/** - * @brief Send a button_change message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_button_change_send_struct(mavlink_channel_t chan, const mavlink_button_change_t* button_change) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_button_change_send(chan, button_change->time_boot_ms, button_change->last_change_ms, button_change->state); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, (const char *)button_change, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_BUTTON_CHANGE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_button_change_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t last_change_ms, uint8_t state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, last_change_ms); - _mav_put_uint8_t(buf, 8, state); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, buf, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -#else - mavlink_button_change_t *packet = (mavlink_button_change_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->last_change_ms = last_change_ms; - packet->state = state; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, (const char *)packet, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE BUTTON_CHANGE UNPACKING - - -/** - * @brief Get field time_boot_ms from button_change message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_button_change_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field last_change_ms from button_change message - * - * @return Time of last change of button state - */ -static inline uint32_t mavlink_msg_button_change_get_last_change_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field state from button_change message - * - * @return Bitmap state of buttons - */ -static inline uint8_t mavlink_msg_button_change_get_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Decode a button_change message into a struct - * - * @param msg The message to decode - * @param button_change C-struct to decode the message contents into - */ -static inline void mavlink_msg_button_change_decode(const mavlink_message_t* msg, mavlink_button_change_t* button_change) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - button_change->time_boot_ms = mavlink_msg_button_change_get_time_boot_ms(msg); - button_change->last_change_ms = mavlink_msg_button_change_get_last_change_ms(msg); - button_change->state = mavlink_msg_button_change_get_state(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_BUTTON_CHANGE_LEN? msg->len : MAVLINK_MSG_ID_BUTTON_CHANGE_LEN; - memset(button_change, 0, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN); - memcpy(button_change, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_camera_capture_status.h b/include/mavlink/v2.0/common/mavlink_msg_camera_capture_status.h deleted file mode 100644 index af52397..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_camera_capture_status.h +++ /dev/null @@ -1,488 +0,0 @@ -#pragma once -// MESSAGE CAMERA_CAPTURE_STATUS PACKING - -#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS 262 - -MAVPACKED( -typedef struct __mavlink_camera_capture_status_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float image_interval; /*< Image capture interval in seconds*/ - float video_framerate; /*< Video frame rate in Hz*/ - uint32_t recording_time_ms; /*< Time in milliseconds since recording started*/ - float available_capacity; /*< Available storage capacity in MiB*/ - uint16_t image_resolution_h; /*< Image resolution in pixels horizontal*/ - uint16_t image_resolution_v; /*< Image resolution in pixels vertical*/ - uint16_t video_resolution_h; /*< Video resolution in pixels horizontal*/ - uint16_t video_resolution_v; /*< Video resolution in pixels vertical*/ - uint8_t camera_id; /*< Camera ID if there are multiple*/ - uint8_t image_status; /*< Current status of image capturing (0: not running, 1: interval capture in progress)*/ - uint8_t video_status; /*< Current status of video capturing (0: not running, 1: capture in progress)*/ -}) mavlink_camera_capture_status_t; - -#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN 31 -#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN 31 -#define MAVLINK_MSG_ID_262_LEN 31 -#define MAVLINK_MSG_ID_262_MIN_LEN 31 - -#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC 69 -#define MAVLINK_MSG_ID_262_CRC 69 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS { \ - 262, \ - "CAMERA_CAPTURE_STATUS", \ - 12, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_capture_status_t, time_boot_ms) }, \ - { "image_interval", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_capture_status_t, image_interval) }, \ - { "video_framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_capture_status_t, video_framerate) }, \ - { "recording_time_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_camera_capture_status_t, recording_time_ms) }, \ - { "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_capture_status_t, available_capacity) }, \ - { "image_resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_camera_capture_status_t, image_resolution_h) }, \ - { "image_resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_camera_capture_status_t, image_resolution_v) }, \ - { "video_resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_capture_status_t, video_resolution_h) }, \ - { "video_resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_camera_capture_status_t, video_resolution_v) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_capture_status_t, camera_id) }, \ - { "image_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_camera_capture_status_t, image_status) }, \ - { "video_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_camera_capture_status_t, video_status) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS { \ - "CAMERA_CAPTURE_STATUS", \ - 12, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_capture_status_t, time_boot_ms) }, \ - { "image_interval", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_capture_status_t, image_interval) }, \ - { "video_framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_capture_status_t, video_framerate) }, \ - { "recording_time_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_camera_capture_status_t, recording_time_ms) }, \ - { "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_capture_status_t, available_capacity) }, \ - { "image_resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_camera_capture_status_t, image_resolution_h) }, \ - { "image_resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_camera_capture_status_t, image_resolution_v) }, \ - { "video_resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_capture_status_t, video_resolution_h) }, \ - { "video_resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_camera_capture_status_t, video_resolution_v) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_capture_status_t, camera_id) }, \ - { "image_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_camera_capture_status_t, image_status) }, \ - { "video_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_camera_capture_status_t, video_status) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_capture_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 time_boot_ms Timestamp (milliseconds since system boot) - * @param camera_id Camera ID if there are multiple - * @param image_status Current status of image capturing (0: not running, 1: interval capture in progress) - * @param video_status Current status of video capturing (0: not running, 1: capture in progress) - * @param image_interval Image capture interval in seconds - * @param video_framerate Video frame rate in Hz - * @param image_resolution_h Image resolution in pixels horizontal - * @param image_resolution_v Image resolution in pixels vertical - * @param video_resolution_h Video resolution in pixels horizontal - * @param video_resolution_v Video resolution in pixels vertical - * @param recording_time_ms Time in milliseconds since recording started - * @param available_capacity Available storage capacity in MiB - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_capture_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t camera_id, uint8_t image_status, uint8_t video_status, float image_interval, float video_framerate, uint16_t image_resolution_h, uint16_t image_resolution_v, uint16_t video_resolution_h, uint16_t video_resolution_v, uint32_t recording_time_ms, float available_capacity) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, image_interval); - _mav_put_float(buf, 8, video_framerate); - _mav_put_uint32_t(buf, 12, recording_time_ms); - _mav_put_float(buf, 16, available_capacity); - _mav_put_uint16_t(buf, 20, image_resolution_h); - _mav_put_uint16_t(buf, 22, image_resolution_v); - _mav_put_uint16_t(buf, 24, video_resolution_h); - _mav_put_uint16_t(buf, 26, video_resolution_v); - _mav_put_uint8_t(buf, 28, camera_id); - _mav_put_uint8_t(buf, 29, image_status); - _mav_put_uint8_t(buf, 30, video_status); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN); -#else - mavlink_camera_capture_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.image_interval = image_interval; - packet.video_framerate = video_framerate; - packet.recording_time_ms = recording_time_ms; - packet.available_capacity = available_capacity; - packet.image_resolution_h = image_resolution_h; - packet.image_resolution_v = image_resolution_v; - packet.video_resolution_h = video_resolution_h; - packet.video_resolution_v = video_resolution_v; - packet.camera_id = camera_id; - packet.image_status = image_status; - packet.video_status = video_status; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -} - -/** - * @brief Pack a camera_capture_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param camera_id Camera ID if there are multiple - * @param image_status Current status of image capturing (0: not running, 1: interval capture in progress) - * @param video_status Current status of video capturing (0: not running, 1: capture in progress) - * @param image_interval Image capture interval in seconds - * @param video_framerate Video frame rate in Hz - * @param image_resolution_h Image resolution in pixels horizontal - * @param image_resolution_v Image resolution in pixels vertical - * @param video_resolution_h Video resolution in pixels horizontal - * @param video_resolution_v Video resolution in pixels vertical - * @param recording_time_ms Time in milliseconds since recording started - * @param available_capacity Available storage capacity in MiB - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_capture_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t camera_id,uint8_t image_status,uint8_t video_status,float image_interval,float video_framerate,uint16_t image_resolution_h,uint16_t image_resolution_v,uint16_t video_resolution_h,uint16_t video_resolution_v,uint32_t recording_time_ms,float available_capacity) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, image_interval); - _mav_put_float(buf, 8, video_framerate); - _mav_put_uint32_t(buf, 12, recording_time_ms); - _mav_put_float(buf, 16, available_capacity); - _mav_put_uint16_t(buf, 20, image_resolution_h); - _mav_put_uint16_t(buf, 22, image_resolution_v); - _mav_put_uint16_t(buf, 24, video_resolution_h); - _mav_put_uint16_t(buf, 26, video_resolution_v); - _mav_put_uint8_t(buf, 28, camera_id); - _mav_put_uint8_t(buf, 29, image_status); - _mav_put_uint8_t(buf, 30, video_status); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN); -#else - mavlink_camera_capture_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.image_interval = image_interval; - packet.video_framerate = video_framerate; - packet.recording_time_ms = recording_time_ms; - packet.available_capacity = available_capacity; - packet.image_resolution_h = image_resolution_h; - packet.image_resolution_v = image_resolution_v; - packet.video_resolution_h = video_resolution_h; - packet.video_resolution_v = video_resolution_v; - packet.camera_id = camera_id; - packet.image_status = image_status; - packet.video_status = video_status; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -} - -/** - * @brief Encode a camera_capture_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_capture_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_capture_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_capture_status_t* camera_capture_status) -{ - return mavlink_msg_camera_capture_status_pack(system_id, component_id, msg, camera_capture_status->time_boot_ms, camera_capture_status->camera_id, camera_capture_status->image_status, camera_capture_status->video_status, camera_capture_status->image_interval, camera_capture_status->video_framerate, camera_capture_status->image_resolution_h, camera_capture_status->image_resolution_v, camera_capture_status->video_resolution_h, camera_capture_status->video_resolution_v, camera_capture_status->recording_time_ms, camera_capture_status->available_capacity); -} - -/** - * @brief Encode a camera_capture_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_capture_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_capture_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_capture_status_t* camera_capture_status) -{ - return mavlink_msg_camera_capture_status_pack_chan(system_id, component_id, chan, msg, camera_capture_status->time_boot_ms, camera_capture_status->camera_id, camera_capture_status->image_status, camera_capture_status->video_status, camera_capture_status->image_interval, camera_capture_status->video_framerate, camera_capture_status->image_resolution_h, camera_capture_status->image_resolution_v, camera_capture_status->video_resolution_h, camera_capture_status->video_resolution_v, camera_capture_status->recording_time_ms, camera_capture_status->available_capacity); -} - -/** - * @brief Send a camera_capture_status message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param camera_id Camera ID if there are multiple - * @param image_status Current status of image capturing (0: not running, 1: interval capture in progress) - * @param video_status Current status of video capturing (0: not running, 1: capture in progress) - * @param image_interval Image capture interval in seconds - * @param video_framerate Video frame rate in Hz - * @param image_resolution_h Image resolution in pixels horizontal - * @param image_resolution_v Image resolution in pixels vertical - * @param video_resolution_h Video resolution in pixels horizontal - * @param video_resolution_v Video resolution in pixels vertical - * @param recording_time_ms Time in milliseconds since recording started - * @param available_capacity Available storage capacity in MiB - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_capture_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t camera_id, uint8_t image_status, uint8_t video_status, float image_interval, float video_framerate, uint16_t image_resolution_h, uint16_t image_resolution_v, uint16_t video_resolution_h, uint16_t video_resolution_v, uint32_t recording_time_ms, float available_capacity) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, image_interval); - _mav_put_float(buf, 8, video_framerate); - _mav_put_uint32_t(buf, 12, recording_time_ms); - _mav_put_float(buf, 16, available_capacity); - _mav_put_uint16_t(buf, 20, image_resolution_h); - _mav_put_uint16_t(buf, 22, image_resolution_v); - _mav_put_uint16_t(buf, 24, video_resolution_h); - _mav_put_uint16_t(buf, 26, video_resolution_v); - _mav_put_uint8_t(buf, 28, camera_id); - _mav_put_uint8_t(buf, 29, image_status); - _mav_put_uint8_t(buf, 30, video_status); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -#else - mavlink_camera_capture_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.image_interval = image_interval; - packet.video_framerate = video_framerate; - packet.recording_time_ms = recording_time_ms; - packet.available_capacity = available_capacity; - packet.image_resolution_h = image_resolution_h; - packet.image_resolution_v = image_resolution_v; - packet.video_resolution_h = video_resolution_h; - packet.video_resolution_v = video_resolution_v; - packet.camera_id = camera_id; - packet.image_status = image_status; - packet.video_status = video_status; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -#endif -} - -/** - * @brief Send a camera_capture_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_capture_status_send_struct(mavlink_channel_t chan, const mavlink_camera_capture_status_t* camera_capture_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_capture_status_send(chan, camera_capture_status->time_boot_ms, camera_capture_status->camera_id, camera_capture_status->image_status, camera_capture_status->video_status, camera_capture_status->image_interval, camera_capture_status->video_framerate, camera_capture_status->image_resolution_h, camera_capture_status->image_resolution_v, camera_capture_status->video_resolution_h, camera_capture_status->video_resolution_v, camera_capture_status->recording_time_ms, camera_capture_status->available_capacity); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, (const char *)camera_capture_status, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_capture_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t camera_id, uint8_t image_status, uint8_t video_status, float image_interval, float video_framerate, uint16_t image_resolution_h, uint16_t image_resolution_v, uint16_t video_resolution_h, uint16_t video_resolution_v, uint32_t recording_time_ms, float available_capacity) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, image_interval); - _mav_put_float(buf, 8, video_framerate); - _mav_put_uint32_t(buf, 12, recording_time_ms); - _mav_put_float(buf, 16, available_capacity); - _mav_put_uint16_t(buf, 20, image_resolution_h); - _mav_put_uint16_t(buf, 22, image_resolution_v); - _mav_put_uint16_t(buf, 24, video_resolution_h); - _mav_put_uint16_t(buf, 26, video_resolution_v); - _mav_put_uint8_t(buf, 28, camera_id); - _mav_put_uint8_t(buf, 29, image_status); - _mav_put_uint8_t(buf, 30, video_status); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -#else - mavlink_camera_capture_status_t *packet = (mavlink_camera_capture_status_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->image_interval = image_interval; - packet->video_framerate = video_framerate; - packet->recording_time_ms = recording_time_ms; - packet->available_capacity = available_capacity; - packet->image_resolution_h = image_resolution_h; - packet->image_resolution_v = image_resolution_v; - packet->video_resolution_h = video_resolution_h; - packet->video_resolution_v = video_resolution_v; - packet->camera_id = camera_id; - packet->image_status = image_status; - packet->video_status = video_status; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_CAPTURE_STATUS UNPACKING - - -/** - * @brief Get field time_boot_ms from camera_capture_status message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_camera_capture_status_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field camera_id from camera_capture_status message - * - * @return Camera ID if there are multiple - */ -static inline uint8_t mavlink_msg_camera_capture_status_get_camera_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field image_status from camera_capture_status message - * - * @return Current status of image capturing (0: not running, 1: interval capture in progress) - */ -static inline uint8_t mavlink_msg_camera_capture_status_get_image_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field video_status from camera_capture_status message - * - * @return Current status of video capturing (0: not running, 1: capture in progress) - */ -static inline uint8_t mavlink_msg_camera_capture_status_get_video_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field image_interval from camera_capture_status message - * - * @return Image capture interval in seconds - */ -static inline float mavlink_msg_camera_capture_status_get_image_interval(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field video_framerate from camera_capture_status message - * - * @return Video frame rate in Hz - */ -static inline float mavlink_msg_camera_capture_status_get_video_framerate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field image_resolution_h from camera_capture_status message - * - * @return Image resolution in pixels horizontal - */ -static inline uint16_t mavlink_msg_camera_capture_status_get_image_resolution_h(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field image_resolution_v from camera_capture_status message - * - * @return Image resolution in pixels vertical - */ -static inline uint16_t mavlink_msg_camera_capture_status_get_image_resolution_v(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field video_resolution_h from camera_capture_status message - * - * @return Video resolution in pixels horizontal - */ -static inline uint16_t mavlink_msg_camera_capture_status_get_video_resolution_h(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field video_resolution_v from camera_capture_status message - * - * @return Video resolution in pixels vertical - */ -static inline uint16_t mavlink_msg_camera_capture_status_get_video_resolution_v(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field recording_time_ms from camera_capture_status message - * - * @return Time in milliseconds since recording started - */ -static inline uint32_t mavlink_msg_camera_capture_status_get_recording_time_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 12); -} - -/** - * @brief Get field available_capacity from camera_capture_status message - * - * @return Available storage capacity in MiB - */ -static inline float mavlink_msg_camera_capture_status_get_available_capacity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a camera_capture_status message into a struct - * - * @param msg The message to decode - * @param camera_capture_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_capture_status_decode(const mavlink_message_t* msg, mavlink_camera_capture_status_t* camera_capture_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_capture_status->time_boot_ms = mavlink_msg_camera_capture_status_get_time_boot_ms(msg); - camera_capture_status->image_interval = mavlink_msg_camera_capture_status_get_image_interval(msg); - camera_capture_status->video_framerate = mavlink_msg_camera_capture_status_get_video_framerate(msg); - camera_capture_status->recording_time_ms = mavlink_msg_camera_capture_status_get_recording_time_ms(msg); - camera_capture_status->available_capacity = mavlink_msg_camera_capture_status_get_available_capacity(msg); - camera_capture_status->image_resolution_h = mavlink_msg_camera_capture_status_get_image_resolution_h(msg); - camera_capture_status->image_resolution_v = mavlink_msg_camera_capture_status_get_image_resolution_v(msg); - camera_capture_status->video_resolution_h = mavlink_msg_camera_capture_status_get_video_resolution_h(msg); - camera_capture_status->video_resolution_v = mavlink_msg_camera_capture_status_get_video_resolution_v(msg); - camera_capture_status->camera_id = mavlink_msg_camera_capture_status_get_camera_id(msg); - camera_capture_status->image_status = mavlink_msg_camera_capture_status_get_image_status(msg); - camera_capture_status->video_status = mavlink_msg_camera_capture_status_get_video_status(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN; - memset(camera_capture_status, 0, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN); - memcpy(camera_capture_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_camera_image_captured.h b/include/mavlink/v2.0/common/mavlink_msg_camera_image_captured.h deleted file mode 100644 index 3b5896c..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_camera_image_captured.h +++ /dev/null @@ -1,456 +0,0 @@ -#pragma once -// MESSAGE CAMERA_IMAGE_CAPTURED PACKING - -#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED 263 - -MAVPACKED( -typedef struct __mavlink_camera_image_captured_t { - uint64_t time_utc; /*< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown.*/ - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int32_t lat; /*< Latitude, expressed as degrees * 1E7 where image was taken*/ - int32_t lon; /*< Longitude, expressed as degrees * 1E7 where capture was taken*/ - int32_t alt; /*< Altitude in meters, expressed as * 1E3 (AMSL, not WGS84) where image was taken*/ - int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1E3 where image was taken*/ - float q[4]; /*< Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0)*/ - int32_t image_index; /*< Zero based index of this image (image count since armed -1)*/ - uint8_t camera_id; /*< Camera ID if there are multiple*/ - int8_t capture_result; /*< Boolean indicating success (1) or failure (0) while capturing this image.*/ - char file_url[205]; /*< URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.*/ -}) mavlink_camera_image_captured_t; - -#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN 255 -#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN 255 -#define MAVLINK_MSG_ID_263_LEN 255 -#define MAVLINK_MSG_ID_263_MIN_LEN 255 - -#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC 133 -#define MAVLINK_MSG_ID_263_CRC 133 - -#define MAVLINK_MSG_CAMERA_IMAGE_CAPTURED_FIELD_Q_LEN 4 -#define MAVLINK_MSG_CAMERA_IMAGE_CAPTURED_FIELD_FILE_URL_LEN 205 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED { \ - 263, \ - "CAMERA_IMAGE_CAPTURED", \ - 11, \ - { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_image_captured_t, time_utc) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_image_captured_t, time_boot_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_image_captured_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_image_captured_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_image_captured_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_image_captured_t, relative_alt) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_image_captured_t, q) }, \ - { "image_index", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_camera_image_captured_t, image_index) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_image_captured_t, camera_id) }, \ - { "capture_result", NULL, MAVLINK_TYPE_INT8_T, 0, 49, offsetof(mavlink_camera_image_captured_t, capture_result) }, \ - { "file_url", NULL, MAVLINK_TYPE_CHAR, 205, 50, offsetof(mavlink_camera_image_captured_t, file_url) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED { \ - "CAMERA_IMAGE_CAPTURED", \ - 11, \ - { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_image_captured_t, time_utc) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_image_captured_t, time_boot_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_image_captured_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_image_captured_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_image_captured_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_image_captured_t, relative_alt) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_image_captured_t, q) }, \ - { "image_index", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_camera_image_captured_t, image_index) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_image_captured_t, camera_id) }, \ - { "capture_result", NULL, MAVLINK_TYPE_INT8_T, 0, 49, offsetof(mavlink_camera_image_captured_t, capture_result) }, \ - { "file_url", NULL, MAVLINK_TYPE_CHAR, 205, 50, offsetof(mavlink_camera_image_captured_t, file_url) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_image_captured 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_boot_ms Timestamp (milliseconds since system boot) - * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. - * @param camera_id Camera ID if there are multiple - * @param lat Latitude, expressed as degrees * 1E7 where image was taken - * @param lon Longitude, expressed as degrees * 1E7 where capture was taken - * @param alt Altitude in meters, expressed as * 1E3 (AMSL, not WGS84) where image was taken - * @param relative_alt Altitude above ground in meters, expressed as * 1E3 where image was taken - * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0) - * @param image_index Zero based index of this image (image count since armed -1) - * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image. - * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_image_captured_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN]; - _mav_put_uint64_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_int32_t(buf, 20, alt); - _mav_put_int32_t(buf, 24, relative_alt); - _mav_put_int32_t(buf, 44, image_index); - _mav_put_uint8_t(buf, 48, camera_id); - _mav_put_int8_t(buf, 49, capture_result); - _mav_put_float_array(buf, 28, q, 4); - _mav_put_char_array(buf, 50, file_url, 205); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN); -#else - mavlink_camera_image_captured_t packet; - packet.time_utc = time_utc; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.image_index = image_index; - packet.camera_id = camera_id; - packet.capture_result = capture_result; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -} - -/** - * @brief Pack a camera_image_captured message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. - * @param camera_id Camera ID if there are multiple - * @param lat Latitude, expressed as degrees * 1E7 where image was taken - * @param lon Longitude, expressed as degrees * 1E7 where capture was taken - * @param alt Altitude in meters, expressed as * 1E3 (AMSL, not WGS84) where image was taken - * @param relative_alt Altitude above ground in meters, expressed as * 1E3 where image was taken - * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0) - * @param image_index Zero based index of this image (image count since armed -1) - * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image. - * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_image_captured_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint64_t time_utc,uint8_t camera_id,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,const float *q,int32_t image_index,int8_t capture_result,const char *file_url) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN]; - _mav_put_uint64_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_int32_t(buf, 20, alt); - _mav_put_int32_t(buf, 24, relative_alt); - _mav_put_int32_t(buf, 44, image_index); - _mav_put_uint8_t(buf, 48, camera_id); - _mav_put_int8_t(buf, 49, capture_result); - _mav_put_float_array(buf, 28, q, 4); - _mav_put_char_array(buf, 50, file_url, 205); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN); -#else - mavlink_camera_image_captured_t packet; - packet.time_utc = time_utc; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.image_index = image_index; - packet.camera_id = camera_id; - packet.capture_result = capture_result; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -} - -/** - * @brief Encode a camera_image_captured struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_image_captured C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_image_captured_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_image_captured_t* camera_image_captured) -{ - return mavlink_msg_camera_image_captured_pack(system_id, component_id, msg, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url); -} - -/** - * @brief Encode a camera_image_captured struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_image_captured C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_image_captured_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_image_captured_t* camera_image_captured) -{ - return mavlink_msg_camera_image_captured_pack_chan(system_id, component_id, chan, msg, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url); -} - -/** - * @brief Send a camera_image_captured message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. - * @param camera_id Camera ID if there are multiple - * @param lat Latitude, expressed as degrees * 1E7 where image was taken - * @param lon Longitude, expressed as degrees * 1E7 where capture was taken - * @param alt Altitude in meters, expressed as * 1E3 (AMSL, not WGS84) where image was taken - * @param relative_alt Altitude above ground in meters, expressed as * 1E3 where image was taken - * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0) - * @param image_index Zero based index of this image (image count since armed -1) - * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image. - * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_image_captured_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN]; - _mav_put_uint64_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_int32_t(buf, 20, alt); - _mav_put_int32_t(buf, 24, relative_alt); - _mav_put_int32_t(buf, 44, image_index); - _mav_put_uint8_t(buf, 48, camera_id); - _mav_put_int8_t(buf, 49, capture_result); - _mav_put_float_array(buf, 28, q, 4); - _mav_put_char_array(buf, 50, file_url, 205); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -#else - mavlink_camera_image_captured_t packet; - packet.time_utc = time_utc; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.image_index = image_index; - packet.camera_id = camera_id; - packet.capture_result = capture_result; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -#endif -} - -/** - * @brief Send a camera_image_captured message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_image_captured_send_struct(mavlink_channel_t chan, const mavlink_camera_image_captured_t* camera_image_captured) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_image_captured_send(chan, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)camera_image_captured, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_image_captured_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_int32_t(buf, 20, alt); - _mav_put_int32_t(buf, 24, relative_alt); - _mav_put_int32_t(buf, 44, image_index); - _mav_put_uint8_t(buf, 48, camera_id); - _mav_put_int8_t(buf, 49, capture_result); - _mav_put_float_array(buf, 28, q, 4); - _mav_put_char_array(buf, 50, file_url, 205); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -#else - mavlink_camera_image_captured_t *packet = (mavlink_camera_image_captured_t *)msgbuf; - packet->time_utc = time_utc; - packet->time_boot_ms = time_boot_ms; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->relative_alt = relative_alt; - packet->image_index = image_index; - packet->camera_id = camera_id; - packet->capture_result = capture_result; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - mav_array_memcpy(packet->file_url, file_url, sizeof(char)*205); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_IMAGE_CAPTURED UNPACKING - - -/** - * @brief Get field time_boot_ms from camera_image_captured message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_camera_image_captured_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field time_utc from camera_image_captured message - * - * @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. - */ -static inline uint64_t mavlink_msg_camera_image_captured_get_time_utc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field camera_id from camera_image_captured message - * - * @return Camera ID if there are multiple - */ -static inline uint8_t mavlink_msg_camera_image_captured_get_camera_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 48); -} - -/** - * @brief Get field lat from camera_image_captured message - * - * @return Latitude, expressed as degrees * 1E7 where image was taken - */ -static inline int32_t mavlink_msg_camera_image_captured_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field lon from camera_image_captured message - * - * @return Longitude, expressed as degrees * 1E7 where capture was taken - */ -static inline int32_t mavlink_msg_camera_image_captured_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field alt from camera_image_captured message - * - * @return Altitude in meters, expressed as * 1E3 (AMSL, not WGS84) where image was taken - */ -static inline int32_t mavlink_msg_camera_image_captured_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field relative_alt from camera_image_captured message - * - * @return Altitude above ground in meters, expressed as * 1E3 where image was taken - */ -static inline int32_t mavlink_msg_camera_image_captured_get_relative_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 24); -} - -/** - * @brief Get field q from camera_image_captured message - * - * @return Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_camera_image_captured_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 28); -} - -/** - * @brief Get field image_index from camera_image_captured message - * - * @return Zero based index of this image (image count since armed -1) - */ -static inline int32_t mavlink_msg_camera_image_captured_get_image_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 44); -} - -/** - * @brief Get field capture_result from camera_image_captured message - * - * @return Boolean indicating success (1) or failure (0) while capturing this image. - */ -static inline int8_t mavlink_msg_camera_image_captured_get_capture_result(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 49); -} - -/** - * @brief Get field file_url from camera_image_captured message - * - * @return URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. - */ -static inline uint16_t mavlink_msg_camera_image_captured_get_file_url(const mavlink_message_t* msg, char *file_url) -{ - return _MAV_RETURN_char_array(msg, file_url, 205, 50); -} - -/** - * @brief Decode a camera_image_captured message into a struct - * - * @param msg The message to decode - * @param camera_image_captured C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_image_captured_decode(const mavlink_message_t* msg, mavlink_camera_image_captured_t* camera_image_captured) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_image_captured->time_utc = mavlink_msg_camera_image_captured_get_time_utc(msg); - camera_image_captured->time_boot_ms = mavlink_msg_camera_image_captured_get_time_boot_ms(msg); - camera_image_captured->lat = mavlink_msg_camera_image_captured_get_lat(msg); - camera_image_captured->lon = mavlink_msg_camera_image_captured_get_lon(msg); - camera_image_captured->alt = mavlink_msg_camera_image_captured_get_alt(msg); - camera_image_captured->relative_alt = mavlink_msg_camera_image_captured_get_relative_alt(msg); - mavlink_msg_camera_image_captured_get_q(msg, camera_image_captured->q); - camera_image_captured->image_index = mavlink_msg_camera_image_captured_get_image_index(msg); - camera_image_captured->camera_id = mavlink_msg_camera_image_captured_get_camera_id(msg); - camera_image_captured->capture_result = mavlink_msg_camera_image_captured_get_capture_result(msg); - mavlink_msg_camera_image_captured_get_file_url(msg, camera_image_captured->file_url); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN; - memset(camera_image_captured, 0, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN); - memcpy(camera_image_captured, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_camera_information.h b/include/mavlink/v2.0/common/mavlink_msg_camera_information.h deleted file mode 100644 index 77d6dd7..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_camera_information.h +++ /dev/null @@ -1,431 +0,0 @@ -#pragma once -// MESSAGE CAMERA_INFORMATION PACKING - -#define MAVLINK_MSG_ID_CAMERA_INFORMATION 259 - -MAVPACKED( -typedef struct __mavlink_camera_information_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float focal_length; /*< Focal length in mm*/ - float sensor_size_h; /*< Image sensor size horizontal in mm*/ - float sensor_size_v; /*< Image sensor size vertical in mm*/ - uint16_t resolution_h; /*< Image resolution in pixels horizontal*/ - uint16_t resolution_v; /*< Image resolution in pixels vertical*/ - uint8_t camera_id; /*< Camera ID if there are multiple*/ - uint8_t vendor_name[32]; /*< Name of the camera vendor*/ - uint8_t model_name[32]; /*< Name of the camera model*/ - uint8_t lense_id; /*< Reserved for a lense ID*/ -}) mavlink_camera_information_t; - -#define MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN 86 -#define MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN 86 -#define MAVLINK_MSG_ID_259_LEN 86 -#define MAVLINK_MSG_ID_259_MIN_LEN 86 - -#define MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC 122 -#define MAVLINK_MSG_ID_259_CRC 122 - -#define MAVLINK_MSG_CAMERA_INFORMATION_FIELD_VENDOR_NAME_LEN 32 -#define MAVLINK_MSG_CAMERA_INFORMATION_FIELD_MODEL_NAME_LEN 32 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION { \ - 259, \ - "CAMERA_INFORMATION", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_information_t, time_boot_ms) }, \ - { "focal_length", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_information_t, focal_length) }, \ - { "sensor_size_h", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_information_t, sensor_size_h) }, \ - { "sensor_size_v", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_information_t, sensor_size_v) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_camera_information_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_camera_information_t, resolution_v) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_camera_information_t, camera_id) }, \ - { "vendor_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 21, offsetof(mavlink_camera_information_t, vendor_name) }, \ - { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 53, offsetof(mavlink_camera_information_t, model_name) }, \ - { "lense_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 85, offsetof(mavlink_camera_information_t, lense_id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION { \ - "CAMERA_INFORMATION", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_information_t, time_boot_ms) }, \ - { "focal_length", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_information_t, focal_length) }, \ - { "sensor_size_h", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_information_t, sensor_size_h) }, \ - { "sensor_size_v", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_information_t, sensor_size_v) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_camera_information_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_camera_information_t, resolution_v) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_camera_information_t, camera_id) }, \ - { "vendor_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 21, offsetof(mavlink_camera_information_t, vendor_name) }, \ - { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 53, offsetof(mavlink_camera_information_t, model_name) }, \ - { "lense_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 85, offsetof(mavlink_camera_information_t, lense_id) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_information 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_boot_ms Timestamp (milliseconds since system boot) - * @param camera_id Camera ID if there are multiple - * @param vendor_name Name of the camera vendor - * @param model_name Name of the camera model - * @param focal_length Focal length in mm - * @param sensor_size_h Image sensor size horizontal in mm - * @param sensor_size_v Image sensor size vertical in mm - * @param resolution_h Image resolution in pixels horizontal - * @param resolution_v Image resolution in pixels vertical - * @param lense_id Reserved for a lense ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t camera_id, const uint8_t *vendor_name, const uint8_t *model_name, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lense_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, focal_length); - _mav_put_float(buf, 8, sensor_size_h); - _mav_put_float(buf, 12, sensor_size_v); - _mav_put_uint16_t(buf, 16, resolution_h); - _mav_put_uint16_t(buf, 18, resolution_v); - _mav_put_uint8_t(buf, 20, camera_id); - _mav_put_uint8_t(buf, 85, lense_id); - _mav_put_uint8_t_array(buf, 21, vendor_name, 32); - _mav_put_uint8_t_array(buf, 53, model_name, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN); -#else - mavlink_camera_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.focal_length = focal_length; - packet.sensor_size_h = sensor_size_h; - packet.sensor_size_v = sensor_size_v; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.camera_id = camera_id; - packet.lense_id = lense_id; - mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_INFORMATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -} - -/** - * @brief Pack a camera_information message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param camera_id Camera ID if there are multiple - * @param vendor_name Name of the camera vendor - * @param model_name Name of the camera model - * @param focal_length Focal length in mm - * @param sensor_size_h Image sensor size horizontal in mm - * @param sensor_size_v Image sensor size vertical in mm - * @param resolution_h Image resolution in pixels horizontal - * @param resolution_v Image resolution in pixels vertical - * @param lense_id Reserved for a lense ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t camera_id,const uint8_t *vendor_name,const uint8_t *model_name,float focal_length,float sensor_size_h,float sensor_size_v,uint16_t resolution_h,uint16_t resolution_v,uint8_t lense_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, focal_length); - _mav_put_float(buf, 8, sensor_size_h); - _mav_put_float(buf, 12, sensor_size_v); - _mav_put_uint16_t(buf, 16, resolution_h); - _mav_put_uint16_t(buf, 18, resolution_v); - _mav_put_uint8_t(buf, 20, camera_id); - _mav_put_uint8_t(buf, 85, lense_id); - _mav_put_uint8_t_array(buf, 21, vendor_name, 32); - _mav_put_uint8_t_array(buf, 53, model_name, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN); -#else - mavlink_camera_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.focal_length = focal_length; - packet.sensor_size_h = sensor_size_h; - packet.sensor_size_v = sensor_size_v; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.camera_id = camera_id; - packet.lense_id = lense_id; - mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_INFORMATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -} - -/** - * @brief Encode a camera_information struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_information_t* camera_information) -{ - return mavlink_msg_camera_information_pack(system_id, component_id, msg, camera_information->time_boot_ms, camera_information->camera_id, camera_information->vendor_name, camera_information->model_name, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lense_id); -} - -/** - * @brief Encode a camera_information struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_information_t* camera_information) -{ - return mavlink_msg_camera_information_pack_chan(system_id, component_id, chan, msg, camera_information->time_boot_ms, camera_information->camera_id, camera_information->vendor_name, camera_information->model_name, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lense_id); -} - -/** - * @brief Send a camera_information message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param camera_id Camera ID if there are multiple - * @param vendor_name Name of the camera vendor - * @param model_name Name of the camera model - * @param focal_length Focal length in mm - * @param sensor_size_h Image sensor size horizontal in mm - * @param sensor_size_v Image sensor size vertical in mm - * @param resolution_h Image resolution in pixels horizontal - * @param resolution_v Image resolution in pixels vertical - * @param lense_id Reserved for a lense ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t camera_id, const uint8_t *vendor_name, const uint8_t *model_name, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lense_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, focal_length); - _mav_put_float(buf, 8, sensor_size_h); - _mav_put_float(buf, 12, sensor_size_v); - _mav_put_uint16_t(buf, 16, resolution_h); - _mav_put_uint16_t(buf, 18, resolution_v); - _mav_put_uint8_t(buf, 20, camera_id); - _mav_put_uint8_t(buf, 85, lense_id); - _mav_put_uint8_t_array(buf, 21, vendor_name, 32); - _mav_put_uint8_t_array(buf, 53, model_name, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -#else - mavlink_camera_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.focal_length = focal_length; - packet.sensor_size_h = sensor_size_h; - packet.sensor_size_v = sensor_size_v; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.camera_id = camera_id; - packet.lense_id = lense_id; - mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -#endif -} - -/** - * @brief Send a camera_information message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_information_send_struct(mavlink_channel_t chan, const mavlink_camera_information_t* camera_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_information_send(chan, camera_information->time_boot_ms, camera_information->camera_id, camera_information->vendor_name, camera_information->model_name, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lense_id); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)camera_information, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t camera_id, const uint8_t *vendor_name, const uint8_t *model_name, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lense_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, focal_length); - _mav_put_float(buf, 8, sensor_size_h); - _mav_put_float(buf, 12, sensor_size_v); - _mav_put_uint16_t(buf, 16, resolution_h); - _mav_put_uint16_t(buf, 18, resolution_v); - _mav_put_uint8_t(buf, 20, camera_id); - _mav_put_uint8_t(buf, 85, lense_id); - _mav_put_uint8_t_array(buf, 21, vendor_name, 32); - _mav_put_uint8_t_array(buf, 53, model_name, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -#else - mavlink_camera_information_t *packet = (mavlink_camera_information_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->focal_length = focal_length; - packet->sensor_size_h = sensor_size_h; - packet->sensor_size_v = sensor_size_v; - packet->resolution_h = resolution_h; - packet->resolution_v = resolution_v; - packet->camera_id = camera_id; - packet->lense_id = lense_id; - mav_array_memcpy(packet->vendor_name, vendor_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet->model_name, model_name, sizeof(uint8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_INFORMATION UNPACKING - - -/** - * @brief Get field time_boot_ms from camera_information message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_camera_information_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field camera_id from camera_information message - * - * @return Camera ID if there are multiple - */ -static inline uint8_t mavlink_msg_camera_information_get_camera_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field vendor_name from camera_information message - * - * @return Name of the camera vendor - */ -static inline uint16_t mavlink_msg_camera_information_get_vendor_name(const mavlink_message_t* msg, uint8_t *vendor_name) -{ - return _MAV_RETURN_uint8_t_array(msg, vendor_name, 32, 21); -} - -/** - * @brief Get field model_name from camera_information message - * - * @return Name of the camera model - */ -static inline uint16_t mavlink_msg_camera_information_get_model_name(const mavlink_message_t* msg, uint8_t *model_name) -{ - return _MAV_RETURN_uint8_t_array(msg, model_name, 32, 53); -} - -/** - * @brief Get field focal_length from camera_information message - * - * @return Focal length in mm - */ -static inline float mavlink_msg_camera_information_get_focal_length(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field sensor_size_h from camera_information message - * - * @return Image sensor size horizontal in mm - */ -static inline float mavlink_msg_camera_information_get_sensor_size_h(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field sensor_size_v from camera_information message - * - * @return Image sensor size vertical in mm - */ -static inline float mavlink_msg_camera_information_get_sensor_size_v(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field resolution_h from camera_information message - * - * @return Image resolution in pixels horizontal - */ -static inline uint16_t mavlink_msg_camera_information_get_resolution_h(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field resolution_v from camera_information message - * - * @return Image resolution in pixels vertical - */ -static inline uint16_t mavlink_msg_camera_information_get_resolution_v(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field lense_id from camera_information message - * - * @return Reserved for a lense ID - */ -static inline uint8_t mavlink_msg_camera_information_get_lense_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 85); -} - -/** - * @brief Decode a camera_information message into a struct - * - * @param msg The message to decode - * @param camera_information C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_information_decode(const mavlink_message_t* msg, mavlink_camera_information_t* camera_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_information->time_boot_ms = mavlink_msg_camera_information_get_time_boot_ms(msg); - camera_information->focal_length = mavlink_msg_camera_information_get_focal_length(msg); - camera_information->sensor_size_h = mavlink_msg_camera_information_get_sensor_size_h(msg); - camera_information->sensor_size_v = mavlink_msg_camera_information_get_sensor_size_v(msg); - camera_information->resolution_h = mavlink_msg_camera_information_get_resolution_h(msg); - camera_information->resolution_v = mavlink_msg_camera_information_get_resolution_v(msg); - camera_information->camera_id = mavlink_msg_camera_information_get_camera_id(msg); - mavlink_msg_camera_information_get_vendor_name(msg, camera_information->vendor_name); - mavlink_msg_camera_information_get_model_name(msg, camera_information->model_name); - camera_information->lense_id = mavlink_msg_camera_information_get_lense_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN; - memset(camera_information, 0, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN); - memcpy(camera_information, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_camera_settings.h b/include/mavlink/v2.0/common/mavlink_msg_camera_settings.h deleted file mode 100644 index ecd3232..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_camera_settings.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE CAMERA_SETTINGS PACKING - -#define MAVLINK_MSG_ID_CAMERA_SETTINGS 260 - -MAVPACKED( -typedef struct __mavlink_camera_settings_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float aperture; /*< Aperture is 1/value*/ - float shutter_speed; /*< Shutter speed in s*/ - float iso_sensitivity; /*< ISO sensitivity*/ - float white_balance; /*< Color temperature in degrees Kelvin*/ - uint8_t camera_id; /*< Camera ID if there are multiple*/ - uint8_t aperture_locked; /*< Aperture locked (0: auto, 1: locked)*/ - uint8_t shutter_speed_locked; /*< Shutter speed locked (0: auto, 1: locked)*/ - uint8_t iso_sensitivity_locked; /*< ISO sensitivity locked (0: auto, 1: locked)*/ - uint8_t white_balance_locked; /*< Color temperature locked (0: auto, 1: locked)*/ - uint8_t mode_id; /*< Reserved for a camera mode ID*/ - uint8_t color_mode_id; /*< Reserved for a color mode ID*/ - uint8_t image_format_id; /*< Reserved for image format ID*/ -}) mavlink_camera_settings_t; - -#define MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN 28 -#define MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN 28 -#define MAVLINK_MSG_ID_260_LEN 28 -#define MAVLINK_MSG_ID_260_MIN_LEN 28 - -#define MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC 8 -#define MAVLINK_MSG_ID_260_CRC 8 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS { \ - 260, \ - "CAMERA_SETTINGS", \ - 13, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_settings_t, time_boot_ms) }, \ - { "aperture", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_settings_t, aperture) }, \ - { "shutter_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_settings_t, shutter_speed) }, \ - { "iso_sensitivity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_settings_t, iso_sensitivity) }, \ - { "white_balance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_settings_t, white_balance) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_camera_settings_t, camera_id) }, \ - { "aperture_locked", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_camera_settings_t, aperture_locked) }, \ - { "shutter_speed_locked", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_camera_settings_t, shutter_speed_locked) }, \ - { "iso_sensitivity_locked", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_camera_settings_t, iso_sensitivity_locked) }, \ - { "white_balance_locked", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_camera_settings_t, white_balance_locked) }, \ - { "mode_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_camera_settings_t, mode_id) }, \ - { "color_mode_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_camera_settings_t, color_mode_id) }, \ - { "image_format_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_camera_settings_t, image_format_id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS { \ - "CAMERA_SETTINGS", \ - 13, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_settings_t, time_boot_ms) }, \ - { "aperture", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_settings_t, aperture) }, \ - { "shutter_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_settings_t, shutter_speed) }, \ - { "iso_sensitivity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_settings_t, iso_sensitivity) }, \ - { "white_balance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_settings_t, white_balance) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_camera_settings_t, camera_id) }, \ - { "aperture_locked", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_camera_settings_t, aperture_locked) }, \ - { "shutter_speed_locked", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_camera_settings_t, shutter_speed_locked) }, \ - { "iso_sensitivity_locked", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_camera_settings_t, iso_sensitivity_locked) }, \ - { "white_balance_locked", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_camera_settings_t, white_balance_locked) }, \ - { "mode_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_camera_settings_t, mode_id) }, \ - { "color_mode_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_camera_settings_t, color_mode_id) }, \ - { "image_format_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_camera_settings_t, image_format_id) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_settings 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_boot_ms Timestamp (milliseconds since system boot) - * @param camera_id Camera ID if there are multiple - * @param aperture Aperture is 1/value - * @param aperture_locked Aperture locked (0: auto, 1: locked) - * @param shutter_speed Shutter speed in s - * @param shutter_speed_locked Shutter speed locked (0: auto, 1: locked) - * @param iso_sensitivity ISO sensitivity - * @param iso_sensitivity_locked ISO sensitivity locked (0: auto, 1: locked) - * @param white_balance Color temperature in degrees Kelvin - * @param white_balance_locked Color temperature locked (0: auto, 1: locked) - * @param mode_id Reserved for a camera mode ID - * @param color_mode_id Reserved for a color mode ID - * @param image_format_id Reserved for image format ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_settings_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t camera_id, float aperture, uint8_t aperture_locked, float shutter_speed, uint8_t shutter_speed_locked, float iso_sensitivity, uint8_t iso_sensitivity_locked, float white_balance, uint8_t white_balance_locked, uint8_t mode_id, uint8_t color_mode_id, uint8_t image_format_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, aperture); - _mav_put_float(buf, 8, shutter_speed); - _mav_put_float(buf, 12, iso_sensitivity); - _mav_put_float(buf, 16, white_balance); - _mav_put_uint8_t(buf, 20, camera_id); - _mav_put_uint8_t(buf, 21, aperture_locked); - _mav_put_uint8_t(buf, 22, shutter_speed_locked); - _mav_put_uint8_t(buf, 23, iso_sensitivity_locked); - _mav_put_uint8_t(buf, 24, white_balance_locked); - _mav_put_uint8_t(buf, 25, mode_id); - _mav_put_uint8_t(buf, 26, color_mode_id); - _mav_put_uint8_t(buf, 27, image_format_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN); -#else - mavlink_camera_settings_t packet; - packet.time_boot_ms = time_boot_ms; - packet.aperture = aperture; - packet.shutter_speed = shutter_speed; - packet.iso_sensitivity = iso_sensitivity; - packet.white_balance = white_balance; - packet.camera_id = camera_id; - packet.aperture_locked = aperture_locked; - packet.shutter_speed_locked = shutter_speed_locked; - packet.iso_sensitivity_locked = iso_sensitivity_locked; - packet.white_balance_locked = white_balance_locked; - packet.mode_id = mode_id; - packet.color_mode_id = color_mode_id; - packet.image_format_id = image_format_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_SETTINGS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -} - -/** - * @brief Pack a camera_settings message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param camera_id Camera ID if there are multiple - * @param aperture Aperture is 1/value - * @param aperture_locked Aperture locked (0: auto, 1: locked) - * @param shutter_speed Shutter speed in s - * @param shutter_speed_locked Shutter speed locked (0: auto, 1: locked) - * @param iso_sensitivity ISO sensitivity - * @param iso_sensitivity_locked ISO sensitivity locked (0: auto, 1: locked) - * @param white_balance Color temperature in degrees Kelvin - * @param white_balance_locked Color temperature locked (0: auto, 1: locked) - * @param mode_id Reserved for a camera mode ID - * @param color_mode_id Reserved for a color mode ID - * @param image_format_id Reserved for image format ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_settings_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t camera_id,float aperture,uint8_t aperture_locked,float shutter_speed,uint8_t shutter_speed_locked,float iso_sensitivity,uint8_t iso_sensitivity_locked,float white_balance,uint8_t white_balance_locked,uint8_t mode_id,uint8_t color_mode_id,uint8_t image_format_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, aperture); - _mav_put_float(buf, 8, shutter_speed); - _mav_put_float(buf, 12, iso_sensitivity); - _mav_put_float(buf, 16, white_balance); - _mav_put_uint8_t(buf, 20, camera_id); - _mav_put_uint8_t(buf, 21, aperture_locked); - _mav_put_uint8_t(buf, 22, shutter_speed_locked); - _mav_put_uint8_t(buf, 23, iso_sensitivity_locked); - _mav_put_uint8_t(buf, 24, white_balance_locked); - _mav_put_uint8_t(buf, 25, mode_id); - _mav_put_uint8_t(buf, 26, color_mode_id); - _mav_put_uint8_t(buf, 27, image_format_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN); -#else - mavlink_camera_settings_t packet; - packet.time_boot_ms = time_boot_ms; - packet.aperture = aperture; - packet.shutter_speed = shutter_speed; - packet.iso_sensitivity = iso_sensitivity; - packet.white_balance = white_balance; - packet.camera_id = camera_id; - packet.aperture_locked = aperture_locked; - packet.shutter_speed_locked = shutter_speed_locked; - packet.iso_sensitivity_locked = iso_sensitivity_locked; - packet.white_balance_locked = white_balance_locked; - packet.mode_id = mode_id; - packet.color_mode_id = color_mode_id; - packet.image_format_id = image_format_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_SETTINGS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -} - -/** - * @brief Encode a camera_settings struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_settings C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_settings_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_settings_t* camera_settings) -{ - return mavlink_msg_camera_settings_pack(system_id, component_id, msg, camera_settings->time_boot_ms, camera_settings->camera_id, camera_settings->aperture, camera_settings->aperture_locked, camera_settings->shutter_speed, camera_settings->shutter_speed_locked, camera_settings->iso_sensitivity, camera_settings->iso_sensitivity_locked, camera_settings->white_balance, camera_settings->white_balance_locked, camera_settings->mode_id, camera_settings->color_mode_id, camera_settings->image_format_id); -} - -/** - * @brief Encode a camera_settings struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_settings C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_settings_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_settings_t* camera_settings) -{ - return mavlink_msg_camera_settings_pack_chan(system_id, component_id, chan, msg, camera_settings->time_boot_ms, camera_settings->camera_id, camera_settings->aperture, camera_settings->aperture_locked, camera_settings->shutter_speed, camera_settings->shutter_speed_locked, camera_settings->iso_sensitivity, camera_settings->iso_sensitivity_locked, camera_settings->white_balance, camera_settings->white_balance_locked, camera_settings->mode_id, camera_settings->color_mode_id, camera_settings->image_format_id); -} - -/** - * @brief Send a camera_settings message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param camera_id Camera ID if there are multiple - * @param aperture Aperture is 1/value - * @param aperture_locked Aperture locked (0: auto, 1: locked) - * @param shutter_speed Shutter speed in s - * @param shutter_speed_locked Shutter speed locked (0: auto, 1: locked) - * @param iso_sensitivity ISO sensitivity - * @param iso_sensitivity_locked ISO sensitivity locked (0: auto, 1: locked) - * @param white_balance Color temperature in degrees Kelvin - * @param white_balance_locked Color temperature locked (0: auto, 1: locked) - * @param mode_id Reserved for a camera mode ID - * @param color_mode_id Reserved for a color mode ID - * @param image_format_id Reserved for image format ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_settings_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t camera_id, float aperture, uint8_t aperture_locked, float shutter_speed, uint8_t shutter_speed_locked, float iso_sensitivity, uint8_t iso_sensitivity_locked, float white_balance, uint8_t white_balance_locked, uint8_t mode_id, uint8_t color_mode_id, uint8_t image_format_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, aperture); - _mav_put_float(buf, 8, shutter_speed); - _mav_put_float(buf, 12, iso_sensitivity); - _mav_put_float(buf, 16, white_balance); - _mav_put_uint8_t(buf, 20, camera_id); - _mav_put_uint8_t(buf, 21, aperture_locked); - _mav_put_uint8_t(buf, 22, shutter_speed_locked); - _mav_put_uint8_t(buf, 23, iso_sensitivity_locked); - _mav_put_uint8_t(buf, 24, white_balance_locked); - _mav_put_uint8_t(buf, 25, mode_id); - _mav_put_uint8_t(buf, 26, color_mode_id); - _mav_put_uint8_t(buf, 27, image_format_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -#else - mavlink_camera_settings_t packet; - packet.time_boot_ms = time_boot_ms; - packet.aperture = aperture; - packet.shutter_speed = shutter_speed; - packet.iso_sensitivity = iso_sensitivity; - packet.white_balance = white_balance; - packet.camera_id = camera_id; - packet.aperture_locked = aperture_locked; - packet.shutter_speed_locked = shutter_speed_locked; - packet.iso_sensitivity_locked = iso_sensitivity_locked; - packet.white_balance_locked = white_balance_locked; - packet.mode_id = mode_id; - packet.color_mode_id = color_mode_id; - packet.image_format_id = image_format_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -#endif -} - -/** - * @brief Send a camera_settings message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_settings_send_struct(mavlink_channel_t chan, const mavlink_camera_settings_t* camera_settings) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_settings_send(chan, camera_settings->time_boot_ms, camera_settings->camera_id, camera_settings->aperture, camera_settings->aperture_locked, camera_settings->shutter_speed, camera_settings->shutter_speed_locked, camera_settings->iso_sensitivity, camera_settings->iso_sensitivity_locked, camera_settings->white_balance, camera_settings->white_balance_locked, camera_settings->mode_id, camera_settings->color_mode_id, camera_settings->image_format_id); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, (const char *)camera_settings, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_settings_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t camera_id, float aperture, uint8_t aperture_locked, float shutter_speed, uint8_t shutter_speed_locked, float iso_sensitivity, uint8_t iso_sensitivity_locked, float white_balance, uint8_t white_balance_locked, uint8_t mode_id, uint8_t color_mode_id, uint8_t image_format_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, aperture); - _mav_put_float(buf, 8, shutter_speed); - _mav_put_float(buf, 12, iso_sensitivity); - _mav_put_float(buf, 16, white_balance); - _mav_put_uint8_t(buf, 20, camera_id); - _mav_put_uint8_t(buf, 21, aperture_locked); - _mav_put_uint8_t(buf, 22, shutter_speed_locked); - _mav_put_uint8_t(buf, 23, iso_sensitivity_locked); - _mav_put_uint8_t(buf, 24, white_balance_locked); - _mav_put_uint8_t(buf, 25, mode_id); - _mav_put_uint8_t(buf, 26, color_mode_id); - _mav_put_uint8_t(buf, 27, image_format_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -#else - mavlink_camera_settings_t *packet = (mavlink_camera_settings_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->aperture = aperture; - packet->shutter_speed = shutter_speed; - packet->iso_sensitivity = iso_sensitivity; - packet->white_balance = white_balance; - packet->camera_id = camera_id; - packet->aperture_locked = aperture_locked; - packet->shutter_speed_locked = shutter_speed_locked; - packet->iso_sensitivity_locked = iso_sensitivity_locked; - packet->white_balance_locked = white_balance_locked; - packet->mode_id = mode_id; - packet->color_mode_id = color_mode_id; - packet->image_format_id = image_format_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_SETTINGS UNPACKING - - -/** - * @brief Get field time_boot_ms from camera_settings message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_camera_settings_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field camera_id from camera_settings message - * - * @return Camera ID if there are multiple - */ -static inline uint8_t mavlink_msg_camera_settings_get_camera_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field aperture from camera_settings message - * - * @return Aperture is 1/value - */ -static inline float mavlink_msg_camera_settings_get_aperture(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field aperture_locked from camera_settings message - * - * @return Aperture locked (0: auto, 1: locked) - */ -static inline uint8_t mavlink_msg_camera_settings_get_aperture_locked(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Get field shutter_speed from camera_settings message - * - * @return Shutter speed in s - */ -static inline float mavlink_msg_camera_settings_get_shutter_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field shutter_speed_locked from camera_settings message - * - * @return Shutter speed locked (0: auto, 1: locked) - */ -static inline uint8_t mavlink_msg_camera_settings_get_shutter_speed_locked(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Get field iso_sensitivity from camera_settings message - * - * @return ISO sensitivity - */ -static inline float mavlink_msg_camera_settings_get_iso_sensitivity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field iso_sensitivity_locked from camera_settings message - * - * @return ISO sensitivity locked (0: auto, 1: locked) - */ -static inline uint8_t mavlink_msg_camera_settings_get_iso_sensitivity_locked(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 23); -} - -/** - * @brief Get field white_balance from camera_settings message - * - * @return Color temperature in degrees Kelvin - */ -static inline float mavlink_msg_camera_settings_get_white_balance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field white_balance_locked from camera_settings message - * - * @return Color temperature locked (0: auto, 1: locked) - */ -static inline uint8_t mavlink_msg_camera_settings_get_white_balance_locked(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field mode_id from camera_settings message - * - * @return Reserved for a camera mode ID - */ -static inline uint8_t mavlink_msg_camera_settings_get_mode_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field color_mode_id from camera_settings message - * - * @return Reserved for a color mode ID - */ -static inline uint8_t mavlink_msg_camera_settings_get_color_mode_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field image_format_id from camera_settings message - * - * @return Reserved for image format ID - */ -static inline uint8_t mavlink_msg_camera_settings_get_image_format_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 27); -} - -/** - * @brief Decode a camera_settings message into a struct - * - * @param msg The message to decode - * @param camera_settings C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_settings_decode(const mavlink_message_t* msg, mavlink_camera_settings_t* camera_settings) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_settings->time_boot_ms = mavlink_msg_camera_settings_get_time_boot_ms(msg); - camera_settings->aperture = mavlink_msg_camera_settings_get_aperture(msg); - camera_settings->shutter_speed = mavlink_msg_camera_settings_get_shutter_speed(msg); - camera_settings->iso_sensitivity = mavlink_msg_camera_settings_get_iso_sensitivity(msg); - camera_settings->white_balance = mavlink_msg_camera_settings_get_white_balance(msg); - camera_settings->camera_id = mavlink_msg_camera_settings_get_camera_id(msg); - camera_settings->aperture_locked = mavlink_msg_camera_settings_get_aperture_locked(msg); - camera_settings->shutter_speed_locked = mavlink_msg_camera_settings_get_shutter_speed_locked(msg); - camera_settings->iso_sensitivity_locked = mavlink_msg_camera_settings_get_iso_sensitivity_locked(msg); - camera_settings->white_balance_locked = mavlink_msg_camera_settings_get_white_balance_locked(msg); - camera_settings->mode_id = mavlink_msg_camera_settings_get_mode_id(msg); - camera_settings->color_mode_id = mavlink_msg_camera_settings_get_color_mode_id(msg); - camera_settings->image_format_id = mavlink_msg_camera_settings_get_image_format_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN; - memset(camera_settings, 0, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN); - memcpy(camera_settings, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_camera_trigger.h b/include/mavlink/v2.0/common/mavlink_msg_camera_trigger.h deleted file mode 100644 index 71bb1c1..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_camera_trigger.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE CAMERA_TRIGGER PACKING - -#define MAVLINK_MSG_ID_CAMERA_TRIGGER 112 - -MAVPACKED( -typedef struct __mavlink_camera_trigger_t { - uint64_t time_usec; /*< Timestamp for the image frame in microseconds*/ - uint32_t seq; /*< Image frame sequence*/ -}) mavlink_camera_trigger_t; - -#define MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN 12 -#define MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN 12 -#define MAVLINK_MSG_ID_112_LEN 12 -#define MAVLINK_MSG_ID_112_MIN_LEN 12 - -#define MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC 174 -#define MAVLINK_MSG_ID_112_CRC 174 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER { \ - 112, \ - "CAMERA_TRIGGER", \ - 2, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_trigger_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_trigger_t, seq) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER { \ - "CAMERA_TRIGGER", \ - 2, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_trigger_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_trigger_t, seq) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_trigger 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 for the image frame in microseconds - * @param seq Image frame sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_trigger_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#else - mavlink_camera_trigger_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -} - -/** - * @brief Pack a camera_trigger message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp for the image frame in microseconds - * @param seq Image frame sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_trigger_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#else - mavlink_camera_trigger_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -} - -/** - * @brief Encode a camera_trigger struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_trigger C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_trigger_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger) -{ - return mavlink_msg_camera_trigger_pack(system_id, component_id, msg, camera_trigger->time_usec, camera_trigger->seq); -} - -/** - * @brief Encode a camera_trigger struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_trigger C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_trigger_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger) -{ - return mavlink_msg_camera_trigger_pack_chan(system_id, component_id, chan, msg, camera_trigger->time_usec, camera_trigger->seq); -} - -/** - * @brief Send a camera_trigger message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp for the image frame in microseconds - * @param seq Image frame sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_trigger_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#else - mavlink_camera_trigger_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#endif -} - -/** - * @brief Send a camera_trigger message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_trigger_send_struct(mavlink_channel_t chan, const mavlink_camera_trigger_t* camera_trigger) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_trigger_send(chan, camera_trigger->time_usec, camera_trigger->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)camera_trigger, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_trigger_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#else - mavlink_camera_trigger_t *packet = (mavlink_camera_trigger_t *)msgbuf; - packet->time_usec = time_usec; - packet->seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_TRIGGER UNPACKING - - -/** - * @brief Get field time_usec from camera_trigger message - * - * @return Timestamp for the image frame in microseconds - */ -static inline uint64_t mavlink_msg_camera_trigger_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field seq from camera_trigger message - * - * @return Image frame sequence - */ -static inline uint32_t mavlink_msg_camera_trigger_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Decode a camera_trigger message into a struct - * - * @param msg The message to decode - * @param camera_trigger C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_trigger_decode(const mavlink_message_t* msg, mavlink_camera_trigger_t* camera_trigger) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_trigger->time_usec = mavlink_msg_camera_trigger_get_time_usec(msg); - camera_trigger->seq = mavlink_msg_camera_trigger_get_seq(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN; - memset(camera_trigger, 0, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); - memcpy(camera_trigger, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_change_operator_control.h b/include/mavlink/v2.0/common/mavlink_msg_change_operator_control.h deleted file mode 100644 index b6e76f7..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_change_operator_control.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE CHANGE_OPERATOR_CONTROL PACKING - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 - -MAVPACKED( -typedef struct __mavlink_change_operator_control_t { - uint8_t target_system; /*< System the GCS requests control for*/ - uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ - uint8_t version; /*< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/ - char passkey[25]; /*< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"*/ -}) mavlink_change_operator_control_t; - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN 28 -#define MAVLINK_MSG_ID_5_LEN 28 -#define MAVLINK_MSG_ID_5_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ - 5, \ - "CHANGE_OPERATOR_CONTROL", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ - { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ - { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ - "CHANGE_OPERATOR_CONTROL", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ - { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ - { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ - } \ -} -#endif - -/** - * @brief Pack a change_operator_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -} - -/** - * @brief Pack a change_operator_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -} - -/** - * @brief Encode a change_operator_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param change_operator_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) -{ - return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); -} - -/** - * @brief Encode a change_operator_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param change_operator_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) -{ - return mavlink_msg_change_operator_control_pack_chan(system_id, component_id, chan, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); -} - -/** - * @brief Send a change_operator_control message - * @param chan MAVLink channel to send the message - * - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#endif -} - -/** - * @brief Send a change_operator_control message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_change_operator_control_send_struct(mavlink_channel_t chan, const mavlink_change_operator_control_t* change_operator_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_change_operator_control_send(chan, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)change_operator_control, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_change_operator_control_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#else - mavlink_change_operator_control_t *packet = (mavlink_change_operator_control_t *)msgbuf; - 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING - - -/** - * @brief Get field target_system from change_operator_control message - * - * @return System the GCS requests control for - */ -static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field control_request from change_operator_control message - * - * @return 0: request control of this MAV, 1: Release control of this MAV - */ -static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field version from change_operator_control message - * - * @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - */ -static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field passkey from change_operator_control message - * - * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - */ -static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey) -{ - return _MAV_RETURN_char_array(msg, passkey, 25, 3); -} - -/** - * @brief Decode a change_operator_control message into a struct - * - * @param msg The message to decode - * @param change_operator_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg); - change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN; - memset(change_operator_control, 0, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); - memcpy(change_operator_control, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_change_operator_control_ack.h b/include/mavlink/v2.0/common/mavlink_msg_change_operator_control_ack.h deleted file mode 100644 index 16bcec8..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_change_operator_control_ack.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 - -MAVPACKED( -typedef struct __mavlink_change_operator_control_ack_t { - uint8_t gcs_system_id; /*< ID of the GCS this message */ - uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ - uint8_t ack; /*< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control*/ -}) mavlink_change_operator_control_ack_t; - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN 3 -#define MAVLINK_MSG_ID_6_LEN 3 -#define MAVLINK_MSG_ID_6_MIN_LEN 3 - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104 -#define MAVLINK_MSG_ID_6_CRC 104 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ - 6, \ - "CHANGE_OPERATOR_CONTROL_ACK", \ - 3, \ - { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ - { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ - "CHANGE_OPERATOR_CONTROL_ACK", \ - 3, \ - { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ - { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ - } \ -} -#endif - -/** - * @brief Pack a change_operator_control_ack 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 gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -} - -/** - * @brief Pack a change_operator_control_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t gcs_system_id,uint8_t control_request,uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -} - -/** - * @brief Encode a change_operator_control_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param change_operator_control_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ - return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); -} - -/** - * @brief Encode a change_operator_control_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param change_operator_control_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ - return mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, chan, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); -} - -/** - * @brief Send a change_operator_control_ack message - * @param chan MAVLink channel to send the message - * - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#endif -} - -/** - * @brief Send a change_operator_control_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_change_operator_control_ack_send_struct(mavlink_channel_t chan, const mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_change_operator_control_ack_send(chan, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)change_operator_control_ack, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_change_operator_control_ack_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#else - mavlink_change_operator_control_ack_t *packet = (mavlink_change_operator_control_ack_t *)msgbuf; - 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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING - - -/** - * @brief Get field gcs_system_id from change_operator_control_ack message - * - * @return ID of the GCS this message - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field control_request from change_operator_control_ack message - * - * @return 0: request control of this MAV, 1: Release control of this MAV - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field ack from change_operator_control_ack message - * - * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a change_operator_control_ack message into a struct - * - * @param msg The message to decode - * @param change_operator_control_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN? msg->len : MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN; - memset(change_operator_control_ack, 0, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); - memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_collision.h b/include/mavlink/v2.0/common/mavlink_msg_collision.h deleted file mode 100644 index b888c20..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_collision.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE COLLISION PACKING - -#define MAVLINK_MSG_ID_COLLISION 247 - -MAVPACKED( -typedef struct __mavlink_collision_t { - uint32_t id; /*< Unique identifier, domain based on src field*/ - float time_to_minimum_delta; /*< Estimated time until collision occurs (seconds)*/ - float altitude_minimum_delta; /*< Closest vertical distance in meters between vehicle and object*/ - float horizontal_minimum_delta; /*< Closest horizontal distance in meteres between vehicle and object*/ - uint8_t src; /*< Collision data source*/ - uint8_t action; /*< Action that is being taken to avoid this collision*/ - uint8_t threat_level; /*< How concerned the aircraft is about this collision*/ -}) mavlink_collision_t; - -#define MAVLINK_MSG_ID_COLLISION_LEN 19 -#define MAVLINK_MSG_ID_COLLISION_MIN_LEN 19 -#define MAVLINK_MSG_ID_247_LEN 19 -#define MAVLINK_MSG_ID_247_MIN_LEN 19 - -#define MAVLINK_MSG_ID_COLLISION_CRC 81 -#define MAVLINK_MSG_ID_247_CRC 81 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COLLISION { \ - 247, \ - "COLLISION", \ - 7, \ - { { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \ - { "time_to_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_collision_t, time_to_minimum_delta) }, \ - { "altitude_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_collision_t, altitude_minimum_delta) }, \ - { "horizontal_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_collision_t, horizontal_minimum_delta) }, \ - { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \ - { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \ - { "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COLLISION { \ - "COLLISION", \ - 7, \ - { { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \ - { "time_to_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_collision_t, time_to_minimum_delta) }, \ - { "altitude_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_collision_t, altitude_minimum_delta) }, \ - { "horizontal_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_collision_t, horizontal_minimum_delta) }, \ - { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \ - { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \ - { "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \ - } \ -} -#endif - -/** - * @brief Pack a collision 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 src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta Estimated time until collision occurs (seconds) - * @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object - * @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_collision_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t src, uint32_t id, uint8_t action, uint8_t threat_level, float time_to_minimum_delta, float altitude_minimum_delta, float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COLLISION_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COLLISION_LEN); -#else - mavlink_collision_t packet; - packet.id = id; - packet.time_to_minimum_delta = time_to_minimum_delta; - packet.altitude_minimum_delta = altitude_minimum_delta; - packet.horizontal_minimum_delta = horizontal_minimum_delta; - packet.src = src; - packet.action = action; - packet.threat_level = threat_level; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COLLISION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COLLISION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -} - -/** - * @brief Pack a collision message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta Estimated time until collision occurs (seconds) - * @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object - * @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_collision_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t src,uint32_t id,uint8_t action,uint8_t threat_level,float time_to_minimum_delta,float altitude_minimum_delta,float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COLLISION_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COLLISION_LEN); -#else - mavlink_collision_t packet; - packet.id = id; - packet.time_to_minimum_delta = time_to_minimum_delta; - packet.altitude_minimum_delta = altitude_minimum_delta; - packet.horizontal_minimum_delta = horizontal_minimum_delta; - packet.src = src; - packet.action = action; - packet.threat_level = threat_level; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COLLISION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COLLISION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -} - -/** - * @brief Encode a collision struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param collision C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_collision_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_collision_t* collision) -{ - return mavlink_msg_collision_pack(system_id, component_id, msg, collision->src, collision->id, collision->action, collision->threat_level, collision->time_to_minimum_delta, collision->altitude_minimum_delta, collision->horizontal_minimum_delta); -} - -/** - * @brief Encode a collision struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param collision C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_collision_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_collision_t* collision) -{ - return mavlink_msg_collision_pack_chan(system_id, component_id, chan, msg, collision->src, collision->id, collision->action, collision->threat_level, collision->time_to_minimum_delta, collision->altitude_minimum_delta, collision->horizontal_minimum_delta); -} - -/** - * @brief Send a collision message - * @param chan MAVLink channel to send the message - * - * @param src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta Estimated time until collision occurs (seconds) - * @param altitude_minimum_delta Closest vertical distance in meters between vehicle and object - * @param horizontal_minimum_delta Closest horizontal distance in meteres between vehicle and object - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_collision_send(mavlink_channel_t chan, uint8_t src, uint32_t id, uint8_t action, uint8_t threat_level, float time_to_minimum_delta, float altitude_minimum_delta, float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COLLISION_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, buf, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#else - mavlink_collision_t packet; - packet.id = id; - packet.time_to_minimum_delta = time_to_minimum_delta; - packet.altitude_minimum_delta = altitude_minimum_delta; - packet.horizontal_minimum_delta = horizontal_minimum_delta; - packet.src = src; - packet.action = action; - packet.threat_level = threat_level; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, (const char *)&packet, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#endif -} - -/** - * @brief Send a collision message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_collision_send_struct(mavlink_channel_t chan, const mavlink_collision_t* collision) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_collision_send(chan, collision->src, collision->id, collision->action, collision->threat_level, collision->time_to_minimum_delta, collision->altitude_minimum_delta, collision->horizontal_minimum_delta); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, (const char *)collision, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COLLISION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_collision_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t src, uint32_t id, uint8_t action, uint8_t threat_level, float time_to_minimum_delta, float altitude_minimum_delta, float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, buf, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#else - mavlink_collision_t *packet = (mavlink_collision_t *)msgbuf; - packet->id = id; - packet->time_to_minimum_delta = time_to_minimum_delta; - packet->altitude_minimum_delta = altitude_minimum_delta; - packet->horizontal_minimum_delta = horizontal_minimum_delta; - packet->src = src; - packet->action = action; - packet->threat_level = threat_level; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, (const char *)packet, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COLLISION UNPACKING - - -/** - * @brief Get field src from collision message - * - * @return Collision data source - */ -static inline uint8_t mavlink_msg_collision_get_src(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field id from collision message - * - * @return Unique identifier, domain based on src field - */ -static inline uint32_t mavlink_msg_collision_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field action from collision message - * - * @return Action that is being taken to avoid this collision - */ -static inline uint8_t mavlink_msg_collision_get_action(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field threat_level from collision message - * - * @return How concerned the aircraft is about this collision - */ -static inline uint8_t mavlink_msg_collision_get_threat_level(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field time_to_minimum_delta from collision message - * - * @return Estimated time until collision occurs (seconds) - */ -static inline float mavlink_msg_collision_get_time_to_minimum_delta(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field altitude_minimum_delta from collision message - * - * @return Closest vertical distance in meters between vehicle and object - */ -static inline float mavlink_msg_collision_get_altitude_minimum_delta(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field horizontal_minimum_delta from collision message - * - * @return Closest horizontal distance in meteres between vehicle and object - */ -static inline float mavlink_msg_collision_get_horizontal_minimum_delta(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a collision message into a struct - * - * @param msg The message to decode - * @param collision C-struct to decode the message contents into - */ -static inline void mavlink_msg_collision_decode(const mavlink_message_t* msg, mavlink_collision_t* collision) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - collision->id = mavlink_msg_collision_get_id(msg); - collision->time_to_minimum_delta = mavlink_msg_collision_get_time_to_minimum_delta(msg); - collision->altitude_minimum_delta = mavlink_msg_collision_get_altitude_minimum_delta(msg); - collision->horizontal_minimum_delta = mavlink_msg_collision_get_horizontal_minimum_delta(msg); - collision->src = mavlink_msg_collision_get_src(msg); - collision->action = mavlink_msg_collision_get_action(msg); - collision->threat_level = mavlink_msg_collision_get_threat_level(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COLLISION_LEN? msg->len : MAVLINK_MSG_ID_COLLISION_LEN; - memset(collision, 0, MAVLINK_MSG_ID_COLLISION_LEN); - memcpy(collision, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_command_ack.h b/include/mavlink/v2.0/common/mavlink_msg_command_ack.h deleted file mode 100644 index 7ace685..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_command_ack.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE COMMAND_ACK PACKING - -#define MAVLINK_MSG_ID_COMMAND_ACK 77 - -MAVPACKED( -typedef struct __mavlink_command_ack_t { - uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/ - uint8_t result; /*< See MAV_RESULT enum*/ -}) mavlink_command_ack_t; - -#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 -#define MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN 3 -#define MAVLINK_MSG_ID_77_LEN 3 -#define MAVLINK_MSG_ID_77_MIN_LEN 3 - -#define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143 -#define MAVLINK_MSG_ID_77_CRC 143 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ - 77, \ - "COMMAND_ACK", \ - 2, \ - { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ - { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ - "COMMAND_ACK", \ - 2, \ - { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ - { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \ - } \ -} -#endif - -/** - * @brief Pack a command_ack 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 command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t command, uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -} - -/** - * @brief Pack a command_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t command,uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -} - -/** - * @brief Encode a command_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) -{ - return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result); -} - -/** - * @brief Encode a command_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) -{ - return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result); -} - -/** - * @brief Send a command_ack message - * @param chan MAVLink channel to send the message - * - * @param command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#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, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#endif -} - -/** - * @brief Send a command_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_command_ack_send_struct(mavlink_channel_t chan, const mavlink_command_ack_t* command_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_command_ack_send(chan, command_ack->command, command_ack->result); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)command_ack, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, result); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#else - mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf; - packet->command = command; - packet->result = result; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_ACK UNPACKING - - -/** - * @brief Get field command from command_ack message - * - * @return Command ID, as defined by MAV_CMD enum. - */ -static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field result from command_ack message - * - * @return See MAV_RESULT enum - */ -static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a command_ack message into a struct - * - * @param msg The message to decode - * @param command_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - command_ack->command = mavlink_msg_command_ack_get_command(msg); - command_ack->result = mavlink_msg_command_ack_get_result(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_ACK_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_ACK_LEN; - memset(command_ack, 0, MAVLINK_MSG_ID_COMMAND_ACK_LEN); - memcpy(command_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_command_int.h b/include/mavlink/v2.0/common/mavlink_msg_command_int.h deleted file mode 100644 index 7636346..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_command_int.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE COMMAND_INT PACKING - -#define MAVLINK_MSG_ID_COMMAND_INT 75 - -MAVPACKED( -typedef struct __mavlink_command_int_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ - int32_t y; /*< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7*/ - float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ - uint16_t command; /*< The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h*/ - uint8_t current; /*< false:0, true:1*/ - uint8_t autocontinue; /*< autocontinue to next wp*/ -}) mavlink_command_int_t; - -#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35 -#define MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN 35 -#define MAVLINK_MSG_ID_75_LEN 35 -#define MAVLINK_MSG_ID_75_MIN_LEN 35 - -#define MAVLINK_MSG_ID_COMMAND_INT_CRC 158 -#define MAVLINK_MSG_ID_75_CRC 158 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \ - 75, \ - "COMMAND_INT", \ - 13, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \ - "COMMAND_INT", \ - 13, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ - } \ -} -#endif - -/** - * @brief Pack a command_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#else - mavlink_command_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -} - -/** - * @brief Pack a command_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#else - mavlink_command_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -} - -/** - * @brief Encode a command_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_int_t* command_int) -{ - return mavlink_msg_command_int_pack(system_id, component_id, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); -} - -/** - * @brief Encode a command_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_int_t* command_int) -{ - return mavlink_msg_command_int_pack_chan(system_id, component_id, chan, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); -} - -/** - * @brief Send a command_int message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_command_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#else - mavlink_command_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#endif -} - -/** - * @brief Send a command_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_command_int_send_struct(mavlink_channel_t chan, const mavlink_command_int_t* command_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_command_int_send(chan, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)command_int, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#else - mavlink_command_int_t *packet = (mavlink_command_int_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->x = x; - packet->y = y; - packet->z = z; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - packet->current = current; - packet->autocontinue = autocontinue; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_INT UNPACKING - - -/** - * @brief Get field target_system from command_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_command_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field target_component from command_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field frame from command_int message - * - * @return The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - */ -static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field command from command_int message - * - * @return The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - */ -static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field current from command_int message - * - * @return false:0, true:1 - */ -static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field autocontinue from command_int message - * - * @return autocontinue to next wp - */ -static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field param1 from command_int message - * - * @return PARAM1, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from command_int message - * - * @return PARAM2, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from command_int message - * - * @return PARAM3, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from command_int message - * - * @return PARAM4, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field x from command_int message - * - * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - */ -static inline int32_t mavlink_msg_command_int_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field y from command_int message - * - * @return PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - */ -static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field z from command_int message - * - * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - */ -static inline float mavlink_msg_command_int_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a command_int message into a struct - * - * @param msg The message to decode - * @param command_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_int_decode(const mavlink_message_t* msg, mavlink_command_int_t* command_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - command_int->param1 = mavlink_msg_command_int_get_param1(msg); - command_int->param2 = mavlink_msg_command_int_get_param2(msg); - command_int->param3 = mavlink_msg_command_int_get_param3(msg); - command_int->param4 = mavlink_msg_command_int_get_param4(msg); - command_int->x = mavlink_msg_command_int_get_x(msg); - command_int->y = mavlink_msg_command_int_get_y(msg); - command_int->z = mavlink_msg_command_int_get_z(msg); - command_int->command = mavlink_msg_command_int_get_command(msg); - command_int->target_system = mavlink_msg_command_int_get_target_system(msg); - command_int->target_component = mavlink_msg_command_int_get_target_component(msg); - command_int->frame = mavlink_msg_command_int_get_frame(msg); - command_int->current = mavlink_msg_command_int_get_current(msg); - command_int->autocontinue = mavlink_msg_command_int_get_autocontinue(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_INT_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_INT_LEN; - memset(command_int, 0, MAVLINK_MSG_ID_COMMAND_INT_LEN); - memcpy(command_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_command_long.h b/include/mavlink/v2.0/common/mavlink_msg_command_long.h deleted file mode 100644 index f7c62cb..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_command_long.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE COMMAND_LONG PACKING - -#define MAVLINK_MSG_ID_COMMAND_LONG 76 - -MAVPACKED( -typedef struct __mavlink_command_long_t { - float param1; /*< Parameter 1, as defined by MAV_CMD enum.*/ - float param2; /*< Parameter 2, as defined by MAV_CMD enum.*/ - float param3; /*< Parameter 3, as defined by MAV_CMD enum.*/ - float param4; /*< Parameter 4, as defined by MAV_CMD enum.*/ - float param5; /*< Parameter 5, as defined by MAV_CMD enum.*/ - float param6; /*< Parameter 6, as defined by MAV_CMD enum.*/ - float param7; /*< Parameter 7, as defined by MAV_CMD enum.*/ - uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/ - uint8_t target_system; /*< System which should execute the command*/ - uint8_t target_component; /*< Component which should execute the command, 0 for all components*/ - uint8_t confirmation; /*< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)*/ -}) mavlink_command_long_t; - -#define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 -#define MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN 33 -#define MAVLINK_MSG_ID_76_LEN 33 -#define MAVLINK_MSG_ID_76_MIN_LEN 33 - -#define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152 -#define MAVLINK_MSG_ID_76_CRC 152 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ - 76, \ - "COMMAND_LONG", \ - 11, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ - { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ - { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ - { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ - { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ - "COMMAND_LONG", \ - 11, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ - { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ - { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ - { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ - { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ - } \ -} -#endif - -/** - * @brief Pack a command_long message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - - 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, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -} - -/** - * @brief Pack a command_long message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - - 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, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -} - -/** - * @brief Encode a command_long struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_long C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_long_t* command_long) -{ - return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); -} - -/** - * @brief Encode a command_long struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_long C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_long_t* command_long) -{ - return mavlink_msg_command_long_pack_chan(system_id, component_id, chan, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); -} - -/** - * @brief Send a command_long message - * @param chan MAVLink channel to send the message - * - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _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, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#endif -} - -/** - * @brief Send a command_long message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_command_long_send_struct(mavlink_channel_t chan, const mavlink_command_long_t* command_long) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_command_long_send(chan, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)command_long, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_long_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _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, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - mavlink_command_long_t *packet = (mavlink_command_long_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->param5 = param5; - packet->param6 = param6; - packet->param7 = param7; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->confirmation = confirmation; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_LONG UNPACKING - - -/** - * @brief Get field target_system from command_long message - * - * @return System which should execute the command - */ -static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field target_component from command_long message - * - * @return Component which should execute the command, 0 for all components - */ -static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field command from command_long message - * - * @return Command ID, as defined by MAV_CMD enum. - */ -static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field confirmation from command_long message - * - * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - */ -static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field param1 from command_long message - * - * @return Parameter 1, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from command_long message - * - * @return Parameter 2, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from command_long message - * - * @return Parameter 3, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from command_long message - * - * @return Parameter 4, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field param5 from command_long message - * - * @return Parameter 5, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field param6 from command_long message - * - * @return Parameter 6, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field param7 from command_long message - * - * @return Parameter 7, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a command_long message into a struct - * - * @param msg The message to decode - * @param command_long C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, mavlink_command_long_t* command_long) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - command_long->param1 = mavlink_msg_command_long_get_param1(msg); - command_long->param2 = mavlink_msg_command_long_get_param2(msg); - command_long->param3 = mavlink_msg_command_long_get_param3(msg); - command_long->param4 = mavlink_msg_command_long_get_param4(msg); - command_long->param5 = mavlink_msg_command_long_get_param5(msg); - command_long->param6 = mavlink_msg_command_long_get_param6(msg); - command_long->param7 = mavlink_msg_command_long_get_param7(msg); - command_long->command = mavlink_msg_command_long_get_command(msg); - command_long->target_system = mavlink_msg_command_long_get_target_system(msg); - command_long->target_component = mavlink_msg_command_long_get_target_component(msg); - command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_LONG_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_LONG_LEN; - memset(command_long, 0, MAVLINK_MSG_ID_COMMAND_LONG_LEN); - memcpy(command_long, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_control_system_state.h b/include/mavlink/v2.0/common/mavlink_msg_control_system_state.h deleted file mode 100644 index 8914b6a..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_control_system_state.h +++ /dev/null @@ -1,607 +0,0 @@ -#pragma once -// MESSAGE CONTROL_SYSTEM_STATE PACKING - -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE 146 - -MAVPACKED( -typedef struct __mavlink_control_system_state_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float x_acc; /*< X acceleration in body frame*/ - float y_acc; /*< Y acceleration in body frame*/ - float z_acc; /*< Z acceleration in body frame*/ - float x_vel; /*< X velocity in body frame*/ - float y_vel; /*< Y velocity in body frame*/ - float z_vel; /*< Z velocity in body frame*/ - float x_pos; /*< X position in local frame*/ - float y_pos; /*< Y position in local frame*/ - float z_pos; /*< Z position in local frame*/ - float airspeed; /*< Airspeed, set to -1 if unknown*/ - float vel_variance[3]; /*< Variance of body velocity estimate*/ - float pos_variance[3]; /*< Variance in local position*/ - float q[4]; /*< The attitude, represented as Quaternion*/ - float roll_rate; /*< Angular rate in roll axis*/ - float pitch_rate; /*< Angular rate in pitch axis*/ - float yaw_rate; /*< Angular rate in yaw axis*/ -}) mavlink_control_system_state_t; - -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN 100 -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN 100 -#define MAVLINK_MSG_ID_146_LEN 100 -#define MAVLINK_MSG_ID_146_MIN_LEN 100 - -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC 103 -#define MAVLINK_MSG_ID_146_CRC 103 - -#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_VEL_VARIANCE_LEN 3 -#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_POS_VARIANCE_LEN 3 -#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \ - 146, \ - "CONTROL_SYSTEM_STATE", \ - 17, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \ - { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \ - { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \ - { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \ - { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \ - { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \ - { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \ - { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \ - { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \ - { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \ - { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \ - { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \ - { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \ - { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \ - { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \ - "CONTROL_SYSTEM_STATE", \ - 17, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \ - { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \ - { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \ - { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \ - { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \ - { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \ - { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \ - { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \ - { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \ - { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \ - { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \ - { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \ - { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \ - { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \ - { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \ - } \ -} -#endif - -/** - * @brief Pack a control_system_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 time_usec Timestamp (micros since boot or Unix epoch) - * @param x_acc X acceleration in body frame - * @param y_acc Y acceleration in body frame - * @param z_acc Z acceleration in body frame - * @param x_vel X velocity in body frame - * @param y_vel Y velocity in body frame - * @param z_vel Z velocity in body frame - * @param x_pos X position in local frame - * @param y_pos Y position in local frame - * @param z_pos Z position in local frame - * @param airspeed Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate Angular rate in roll axis - * @param pitch_rate Angular rate in pitch axis - * @param yaw_rate Angular rate in yaw axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#else - mavlink_control_system_state_t packet; - packet.time_usec = time_usec; - packet.x_acc = x_acc; - packet.y_acc = y_acc; - packet.z_acc = z_acc; - packet.x_vel = x_vel; - packet.y_vel = y_vel; - packet.z_vel = z_vel; - packet.x_pos = x_pos; - packet.y_pos = y_pos; - packet.z_pos = z_pos; - packet.airspeed = airspeed; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -} - -/** - * @brief Pack a control_system_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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param x_acc X acceleration in body frame - * @param y_acc Y acceleration in body frame - * @param z_acc Z acceleration in body frame - * @param x_vel X velocity in body frame - * @param y_vel Y velocity in body frame - * @param z_vel Z velocity in body frame - * @param x_pos X position in local frame - * @param y_pos Y position in local frame - * @param z_pos Z position in local frame - * @param airspeed Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate Angular rate in roll axis - * @param pitch_rate Angular rate in pitch axis - * @param yaw_rate Angular rate in yaw axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_control_system_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float x_acc,float y_acc,float z_acc,float x_vel,float y_vel,float z_vel,float x_pos,float y_pos,float z_pos,float airspeed,const float *vel_variance,const float *pos_variance,const float *q,float roll_rate,float pitch_rate,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#else - mavlink_control_system_state_t packet; - packet.time_usec = time_usec; - packet.x_acc = x_acc; - packet.y_acc = y_acc; - packet.z_acc = z_acc; - packet.x_vel = x_vel; - packet.y_vel = y_vel; - packet.z_vel = z_vel; - packet.x_pos = x_pos; - packet.y_pos = y_pos; - packet.z_pos = z_pos; - packet.airspeed = airspeed; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -} - -/** - * @brief Encode a control_system_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param control_system_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_control_system_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state) -{ - return mavlink_msg_control_system_state_pack(system_id, component_id, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); -} - -/** - * @brief Encode a control_system_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param control_system_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_control_system_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state) -{ - return mavlink_msg_control_system_state_pack_chan(system_id, component_id, chan, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); -} - -/** - * @brief Send a control_system_state message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param x_acc X acceleration in body frame - * @param y_acc Y acceleration in body frame - * @param z_acc Z acceleration in body frame - * @param x_vel X velocity in body frame - * @param y_vel Y velocity in body frame - * @param z_vel Z velocity in body frame - * @param x_pos X position in local frame - * @param y_pos Y position in local frame - * @param z_pos Z position in local frame - * @param airspeed Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate Angular rate in roll axis - * @param pitch_rate Angular rate in pitch axis - * @param yaw_rate Angular rate in yaw axis - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_control_system_state_send(mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#else - mavlink_control_system_state_t packet; - packet.time_usec = time_usec; - packet.x_acc = x_acc; - packet.y_acc = y_acc; - packet.z_acc = z_acc; - packet.x_vel = x_vel; - packet.y_vel = y_vel; - packet.z_vel = z_vel; - packet.x_pos = x_pos; - packet.y_pos = y_pos; - packet.z_pos = z_pos; - packet.airspeed = airspeed; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)&packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#endif -} - -/** - * @brief Send a control_system_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_control_system_state_send_struct(mavlink_channel_t chan, const mavlink_control_system_state_t* control_system_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_control_system_state_send(chan, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)control_system_state, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_control_system_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#else - mavlink_control_system_state_t *packet = (mavlink_control_system_state_t *)msgbuf; - packet->time_usec = time_usec; - packet->x_acc = x_acc; - packet->y_acc = y_acc; - packet->z_acc = z_acc; - packet->x_vel = x_vel; - packet->y_vel = y_vel; - packet->z_vel = z_vel; - packet->x_pos = x_pos; - packet->y_pos = y_pos; - packet->z_pos = z_pos; - packet->airspeed = airspeed; - packet->roll_rate = roll_rate; - packet->pitch_rate = pitch_rate; - packet->yaw_rate = yaw_rate; - mav_array_memcpy(packet->vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet->pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CONTROL_SYSTEM_STATE UNPACKING - - -/** - * @brief Get field time_usec from control_system_state message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_control_system_state_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x_acc from control_system_state message - * - * @return X acceleration in body frame - */ -static inline float mavlink_msg_control_system_state_get_x_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y_acc from control_system_state message - * - * @return Y acceleration in body frame - */ -static inline float mavlink_msg_control_system_state_get_y_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z_acc from control_system_state message - * - * @return Z acceleration in body frame - */ -static inline float mavlink_msg_control_system_state_get_z_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field x_vel from control_system_state message - * - * @return X velocity in body frame - */ -static inline float mavlink_msg_control_system_state_get_x_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field y_vel from control_system_state message - * - * @return Y velocity in body frame - */ -static inline float mavlink_msg_control_system_state_get_y_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field z_vel from control_system_state message - * - * @return Z velocity in body frame - */ -static inline float mavlink_msg_control_system_state_get_z_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field x_pos from control_system_state message - * - * @return X position in local frame - */ -static inline float mavlink_msg_control_system_state_get_x_pos(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field y_pos from control_system_state message - * - * @return Y position in local frame - */ -static inline float mavlink_msg_control_system_state_get_y_pos(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field z_pos from control_system_state message - * - * @return Z position in local frame - */ -static inline float mavlink_msg_control_system_state_get_z_pos(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field airspeed from control_system_state message - * - * @return Airspeed, set to -1 if unknown - */ -static inline float mavlink_msg_control_system_state_get_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field vel_variance from control_system_state message - * - * @return Variance of body velocity estimate - */ -static inline uint16_t mavlink_msg_control_system_state_get_vel_variance(const mavlink_message_t* msg, float *vel_variance) -{ - return _MAV_RETURN_float_array(msg, vel_variance, 3, 48); -} - -/** - * @brief Get field pos_variance from control_system_state message - * - * @return Variance in local position - */ -static inline uint16_t mavlink_msg_control_system_state_get_pos_variance(const mavlink_message_t* msg, float *pos_variance) -{ - return _MAV_RETURN_float_array(msg, pos_variance, 3, 60); -} - -/** - * @brief Get field q from control_system_state message - * - * @return The attitude, represented as Quaternion - */ -static inline uint16_t mavlink_msg_control_system_state_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 72); -} - -/** - * @brief Get field roll_rate from control_system_state message - * - * @return Angular rate in roll axis - */ -static inline float mavlink_msg_control_system_state_get_roll_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 88); -} - -/** - * @brief Get field pitch_rate from control_system_state message - * - * @return Angular rate in pitch axis - */ -static inline float mavlink_msg_control_system_state_get_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 92); -} - -/** - * @brief Get field yaw_rate from control_system_state message - * - * @return Angular rate in yaw axis - */ -static inline float mavlink_msg_control_system_state_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 96); -} - -/** - * @brief Decode a control_system_state message into a struct - * - * @param msg The message to decode - * @param control_system_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_control_system_state_decode(const mavlink_message_t* msg, mavlink_control_system_state_t* control_system_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - control_system_state->time_usec = mavlink_msg_control_system_state_get_time_usec(msg); - control_system_state->x_acc = mavlink_msg_control_system_state_get_x_acc(msg); - control_system_state->y_acc = mavlink_msg_control_system_state_get_y_acc(msg); - control_system_state->z_acc = mavlink_msg_control_system_state_get_z_acc(msg); - control_system_state->x_vel = mavlink_msg_control_system_state_get_x_vel(msg); - control_system_state->y_vel = mavlink_msg_control_system_state_get_y_vel(msg); - control_system_state->z_vel = mavlink_msg_control_system_state_get_z_vel(msg); - control_system_state->x_pos = mavlink_msg_control_system_state_get_x_pos(msg); - control_system_state->y_pos = mavlink_msg_control_system_state_get_y_pos(msg); - control_system_state->z_pos = mavlink_msg_control_system_state_get_z_pos(msg); - control_system_state->airspeed = mavlink_msg_control_system_state_get_airspeed(msg); - mavlink_msg_control_system_state_get_vel_variance(msg, control_system_state->vel_variance); - mavlink_msg_control_system_state_get_pos_variance(msg, control_system_state->pos_variance); - mavlink_msg_control_system_state_get_q(msg, control_system_state->q); - control_system_state->roll_rate = mavlink_msg_control_system_state_get_roll_rate(msg); - control_system_state->pitch_rate = mavlink_msg_control_system_state_get_pitch_rate(msg); - control_system_state->yaw_rate = mavlink_msg_control_system_state_get_yaw_rate(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN? msg->len : MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN; - memset(control_system_state, 0, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); - memcpy(control_system_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_data_stream.h b/include/mavlink/v2.0/common/mavlink_msg_data_stream.h deleted file mode 100644 index cceca20..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_data_stream.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE DATA_STREAM PACKING - -#define MAVLINK_MSG_ID_DATA_STREAM 67 - -MAVPACKED( -typedef struct __mavlink_data_stream_t { - uint16_t message_rate; /*< The message rate*/ - uint8_t stream_id; /*< The ID of the requested data stream*/ - uint8_t on_off; /*< 1 stream is enabled, 0 stream is stopped.*/ -}) mavlink_data_stream_t; - -#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4 -#define MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN 4 -#define MAVLINK_MSG_ID_67_LEN 4 -#define MAVLINK_MSG_ID_67_MIN_LEN 4 - -#define MAVLINK_MSG_ID_DATA_STREAM_CRC 21 -#define MAVLINK_MSG_ID_67_CRC 21 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ - 67, \ - "DATA_STREAM", \ - 3, \ - { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ - { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ - { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ - "DATA_STREAM", \ - 3, \ - { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ - { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ - { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ - } \ -} -#endif - -/** - * @brief Pack a data_stream 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 stream_id The ID of the requested data stream - * @param message_rate The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t stream_id, uint16_t message_rate, uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -} - -/** - * @brief Pack a data_stream message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param stream_id The ID of the requested data stream - * @param message_rate The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t stream_id,uint16_t message_rate,uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -} - -/** - * @brief Encode a data_stream struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) -{ - return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); -} - -/** - * @brief Encode a data_stream struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) -{ - return mavlink_msg_data_stream_pack_chan(system_id, component_id, chan, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); -} - -/** - * @brief Send a data_stream message - * @param chan MAVLink channel to send the message - * - * @param stream_id The ID of the requested data stream - * @param message_rate The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#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, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#endif -} - -/** - * @brief Send a data_stream message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_data_stream_send_struct(mavlink_channel_t chan, const mavlink_data_stream_t* data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_data_stream_send(chan, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)data_stream, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data_stream_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#else - mavlink_data_stream_t *packet = (mavlink_data_stream_t *)msgbuf; - 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, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DATA_STREAM UNPACKING - - -/** - * @brief Get field stream_id from data_stream message - * - * @return The ID of the requested data stream - */ -static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field message_rate from data_stream message - * - * @return The message rate - */ -static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field on_off from data_stream message - * - * @return 1 stream is enabled, 0 stream is stopped. - */ -static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Decode a data_stream message into a struct - * - * @param msg The message to decode - * @param data_stream C-struct to decode the message contents into - */ -static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, mavlink_data_stream_t* data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - data_stream->message_rate = mavlink_msg_data_stream_get_message_rate(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 - uint8_t len = msg->len < MAVLINK_MSG_ID_DATA_STREAM_LEN? msg->len : MAVLINK_MSG_ID_DATA_STREAM_LEN; - memset(data_stream, 0, MAVLINK_MSG_ID_DATA_STREAM_LEN); - memcpy(data_stream, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_data_transmission_handshake.h b/include/mavlink/v2.0/common/mavlink_msg_data_transmission_handshake.h deleted file mode 100644 index f607e39..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_data_transmission_handshake.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130 - -MAVPACKED( -typedef struct __mavlink_data_transmission_handshake_t { - uint32_t size; /*< total data size in bytes (set on ACK only)*/ - uint16_t width; /*< Width of a matrix or image*/ - uint16_t height; /*< Height of a matrix or image*/ - uint16_t packets; /*< number of packets beeing sent (set on ACK only)*/ - uint8_t type; /*< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)*/ - uint8_t payload; /*< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)*/ - uint8_t jpg_quality; /*< JPEG quality out of [1,100]*/ -}) mavlink_data_transmission_handshake_t; - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13 -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN 13 -#define MAVLINK_MSG_ID_130_LEN 13 -#define MAVLINK_MSG_ID_130_MIN_LEN 13 - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29 -#define MAVLINK_MSG_ID_130_CRC 29 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ - 130, \ - "DATA_TRANSMISSION_HANDSHAKE", \ - 7, \ - { { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ - { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ - { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ - { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ - { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ - "DATA_TRANSMISSION_HANDSHAKE", \ - 7, \ - { { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ - { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ - { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ - { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ - { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ - } \ -} -#endif - -/** - * @brief Pack a data_transmission_handshake message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - - 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, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -} - -/** - * @brief Pack a data_transmission_handshake message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint16_t packets,uint8_t payload,uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - - 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, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -} - -/** - * @brief Encode a data_transmission_handshake struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data_transmission_handshake C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ - return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); -} - -/** - * @brief Encode a data_transmission_handshake struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data_transmission_handshake C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ - return mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, chan, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); -} - -/** - * @brief Send a data_transmission_handshake message - * @param chan MAVLink channel to send the message - * - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#endif -} - -/** - * @brief Send a data_transmission_handshake message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_data_transmission_handshake_send_struct(mavlink_channel_t chan, const mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_data_transmission_handshake_send(chan, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)data_transmission_handshake, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data_transmission_handshake_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, size); - _mav_put_uint16_t(buf, 4, width); - _mav_put_uint16_t(buf, 6, height); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - mavlink_data_transmission_handshake_t *packet = (mavlink_data_transmission_handshake_t *)msgbuf; - packet->size = size; - packet->width = width; - packet->height = height; - packet->packets = packets; - packet->type = type; - packet->payload = payload; - packet->jpg_quality = jpg_quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING - - -/** - * @brief Get field type from data_transmission_handshake message - * - * @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field size from data_transmission_handshake message - * - * @return total data size in bytes (set on ACK only) - */ -static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field width from data_transmission_handshake message - * - * @return Width of a matrix or image - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field height from data_transmission_handshake message - * - * @return Height of a matrix or image - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field packets from data_transmission_handshake message - * - * @return number of packets beeing sent (set on ACK only) - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field payload from data_transmission_handshake message - * - * @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field jpg_quality from data_transmission_handshake message - * - * @return JPEG quality out of [1,100] - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Decode a data_transmission_handshake message into a struct - * - * @param msg The message to decode - * @param data_transmission_handshake C-struct to decode the message contents into - */ -static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg); - data_transmission_handshake->width = mavlink_msg_data_transmission_handshake_get_width(msg); - data_transmission_handshake->height = mavlink_msg_data_transmission_handshake_get_height(msg); - data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg); - data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN? msg->len : MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN; - memset(data_transmission_handshake, 0, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); - memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_debug.h b/include/mavlink/v2.0/common/mavlink_msg_debug.h deleted file mode 100644 index d762a89..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_debug.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE DEBUG PACKING - -#define MAVLINK_MSG_ID_DEBUG 254 - -MAVPACKED( -typedef struct __mavlink_debug_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float value; /*< DEBUG value*/ - uint8_t ind; /*< index of debug variable*/ -}) mavlink_debug_t; - -#define MAVLINK_MSG_ID_DEBUG_LEN 9 -#define MAVLINK_MSG_ID_DEBUG_MIN_LEN 9 -#define MAVLINK_MSG_ID_254_LEN 9 -#define MAVLINK_MSG_ID_254_MIN_LEN 9 - -#define MAVLINK_MSG_ID_DEBUG_CRC 46 -#define MAVLINK_MSG_ID_254_CRC 46 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DEBUG { \ - 254, \ - "DEBUG", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ - { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DEBUG { \ - "DEBUG", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ - { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ - } \ -} -#endif - -/** - * @brief Pack a debug 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_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t ind, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_DEBUG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -} - -/** - * @brief Pack a debug message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t ind,float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_DEBUG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -} - -/** - * @brief Encode a debug struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param debug C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug) -{ - return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value); -} - -/** - * @brief Encode a debug struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param debug C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_t* debug) -{ - return mavlink_msg_debug_pack_chan(system_id, component_id, chan, msg, debug->time_boot_ms, debug->ind, debug->value); -} - -/** - * @brief Send a debug message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#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, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#endif -} - -/** - * @brief Send a debug message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_debug_send_struct(mavlink_channel_t chan, const mavlink_debug_t* debug) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_debug_send(chan, debug->time_boot_ms, debug->ind, debug->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)debug, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DEBUG_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_debug_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#else - mavlink_debug_t *packet = (mavlink_debug_t *)msgbuf; - 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, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DEBUG UNPACKING - - -/** - * @brief Get field time_boot_ms from debug message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field ind from debug message - * - * @return index of debug variable - */ -static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field value from debug message - * - * @return DEBUG value - */ -static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Decode a debug message into a struct - * - * @param msg The message to decode - * @param debug C-struct to decode the message contents into - */ -static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - debug->time_boot_ms = mavlink_msg_debug_get_time_boot_ms(msg); - debug->value = mavlink_msg_debug_get_value(msg); - debug->ind = mavlink_msg_debug_get_ind(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DEBUG_LEN? msg->len : MAVLINK_MSG_ID_DEBUG_LEN; - memset(debug, 0, MAVLINK_MSG_ID_DEBUG_LEN); - memcpy(debug, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_debug_vect.h b/include/mavlink/v2.0/common/mavlink_msg_debug_vect.h deleted file mode 100644 index ac485af..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_debug_vect.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE DEBUG_VECT PACKING - -#define MAVLINK_MSG_ID_DEBUG_VECT 250 - -MAVPACKED( -typedef struct __mavlink_debug_vect_t { - uint64_t time_usec; /*< Timestamp*/ - float x; /*< x*/ - float y; /*< y*/ - float z; /*< z*/ - char name[10]; /*< Name*/ -}) mavlink_debug_vect_t; - -#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 -#define MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN 30 -#define MAVLINK_MSG_ID_250_LEN 30 -#define MAVLINK_MSG_ID_250_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ - 250, \ - "DEBUG_VECT", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ - "DEBUG_VECT", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ - } \ -} -#endif - -/** - * @brief Pack a debug_vect 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 name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *name, uint64_t time_usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - 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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -} - -/** - * @brief Pack a debug_vect message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *name,uint64_t time_usec,float x,float y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - 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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -} - -/** - * @brief Encode a debug_vect struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param debug_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) -{ - return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); -} - -/** - * @brief Encode a debug_vect struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param debug_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) -{ - return mavlink_msg_debug_vect_pack_chan(system_id, component_id, chan, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); -} - -/** - * @brief Send a debug_vect message - * @param chan MAVLink channel to send the message - * - * @param name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - 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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#endif -} - -/** - * @brief Send a debug_vect message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_debug_vect_send_struct(mavlink_channel_t chan, const mavlink_debug_vect_t* debug_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_debug_vect_send(chan, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)debug_vect, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DEBUG_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_debug_vect_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - mavlink_debug_vect_t *packet = (mavlink_debug_vect_t *)msgbuf; - packet->time_usec = time_usec; - packet->x = x; - 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, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DEBUG_VECT UNPACKING - - -/** - * @brief Get field name from debug_vect message - * - * @return Name - */ -static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 20); -} - -/** - * @brief Get field time_usec from debug_vect message - * - * @return Timestamp - */ -static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from debug_vect message - * - * @return x - */ -static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from debug_vect message - * - * @return y - */ -static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from debug_vect message - * - * @return z - */ -static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a debug_vect message into a struct - * - * @param msg The message to decode - * @param debug_vect C-struct to decode the message contents into - */ -static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg); - debug_vect->x = mavlink_msg_debug_vect_get_x(msg); - debug_vect->y = mavlink_msg_debug_vect_get_y(msg); - debug_vect->z = mavlink_msg_debug_vect_get_z(msg); - mavlink_msg_debug_vect_get_name(msg, debug_vect->name); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DEBUG_VECT_LEN? msg->len : MAVLINK_MSG_ID_DEBUG_VECT_LEN; - memset(debug_vect, 0, MAVLINK_MSG_ID_DEBUG_VECT_LEN); - memcpy(debug_vect, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_distance_sensor.h b/include/mavlink/v2.0/common/mavlink_msg_distance_sensor.h deleted file mode 100644 index 2a52e69..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_distance_sensor.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE DISTANCE_SENSOR PACKING - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR 132 - -MAVPACKED( -typedef struct __mavlink_distance_sensor_t { - uint32_t time_boot_ms; /*< Time since system boot*/ - uint16_t min_distance; /*< Minimum distance the sensor can measure in centimeters*/ - uint16_t max_distance; /*< Maximum distance the sensor can measure in centimeters*/ - uint16_t current_distance; /*< Current distance reading*/ - uint8_t type; /*< Type from MAV_DISTANCE_SENSOR enum.*/ - uint8_t id; /*< Onboard ID of the sensor*/ - uint8_t orientation; /*< Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.*/ - uint8_t covariance; /*< Measurement covariance in centimeters, 0 for unknown / invalid readings*/ -}) mavlink_distance_sensor_t; - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14 -#define MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN 14 -#define MAVLINK_MSG_ID_132_LEN 14 -#define MAVLINK_MSG_ID_132_MIN_LEN 14 - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85 -#define MAVLINK_MSG_ID_132_CRC 85 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \ - 132, \ - "DISTANCE_SENSOR", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \ - { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \ - { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \ - { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \ - { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \ - { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \ - "DISTANCE_SENSOR", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \ - { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \ - { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \ - { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \ - { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \ - { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \ - } \ -} -#endif - -/** - * @brief Pack a distance_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_boot_ms Time since system boot - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -} - -/** - * @brief Pack a distance_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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Time since system boot - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t type,uint8_t id,uint8_t orientation,uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -} - -/** - * @brief Encode a distance_sensor struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param distance_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) -{ - return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); -} - -/** - * @brief Encode a distance_sensor struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param distance_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) -{ - return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); -} - -/** - * @brief Send a distance_sensor message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Time since system boot - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#endif -} - -/** - * @brief Send a distance_sensor message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_distance_sensor_send_struct(mavlink_channel_t chan, const mavlink_distance_sensor_t* distance_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_distance_sensor_send(chan, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)distance_sensor, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->min_distance = min_distance; - packet->max_distance = max_distance; - packet->current_distance = current_distance; - packet->type = type; - packet->id = id; - packet->orientation = orientation; - packet->covariance = covariance; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DISTANCE_SENSOR UNPACKING - - -/** - * @brief Get field time_boot_ms from distance_sensor message - * - * @return Time since system boot - */ -static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field min_distance from distance_sensor message - * - * @return Minimum distance the sensor can measure in centimeters - */ -static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field max_distance from distance_sensor message - * - * @return Maximum distance the sensor can measure in centimeters - */ -static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field current_distance from distance_sensor message - * - * @return Current distance reading - */ -static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field type from distance_sensor message - * - * @return Type from MAV_DISTANCE_SENSOR enum. - */ -static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field id from distance_sensor message - * - * @return Onboard ID of the sensor - */ -static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field orientation from distance_sensor message - * - * @return Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - */ -static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field covariance from distance_sensor message - * - * @return Measurement covariance in centimeters, 0 for unknown / invalid readings - */ -static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Decode a distance_sensor message into a struct - * - * @param msg The message to decode - * @param distance_sensor C-struct to decode the message contents into - */ -static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* msg, mavlink_distance_sensor_t* distance_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - distance_sensor->time_boot_ms = mavlink_msg_distance_sensor_get_time_boot_ms(msg); - distance_sensor->min_distance = mavlink_msg_distance_sensor_get_min_distance(msg); - distance_sensor->max_distance = mavlink_msg_distance_sensor_get_max_distance(msg); - distance_sensor->current_distance = mavlink_msg_distance_sensor_get_current_distance(msg); - distance_sensor->type = mavlink_msg_distance_sensor_get_type(msg); - distance_sensor->id = mavlink_msg_distance_sensor_get_id(msg); - distance_sensor->orientation = mavlink_msg_distance_sensor_get_orientation(msg); - distance_sensor->covariance = mavlink_msg_distance_sensor_get_covariance(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN; - memset(distance_sensor, 0, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); - memcpy(distance_sensor, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_encapsulated_data.h b/include/mavlink/v2.0/common/mavlink_msg_encapsulated_data.h deleted file mode 100644 index 5e9bc92..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_encapsulated_data.h +++ /dev/null @@ -1,230 +0,0 @@ -#pragma once -// MESSAGE ENCAPSULATED_DATA PACKING - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 131 - -MAVPACKED( -typedef struct __mavlink_encapsulated_data_t { - uint16_t seqnr; /*< sequence number (starting with 0 on every transmission)*/ - uint8_t data[253]; /*< image data bytes*/ -}) mavlink_encapsulated_data_t; - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255 -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN 255 -#define MAVLINK_MSG_ID_131_LEN 255 -#define MAVLINK_MSG_ID_131_MIN_LEN 255 - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223 -#define MAVLINK_MSG_ID_131_CRC 223 - -#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \ - 131, \ - "ENCAPSULATED_DATA", \ - 2, \ - { { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \ - "ENCAPSULATED_DATA", \ - 2, \ - { { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a encapsulated_data 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 seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seqnr, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -} - -/** - * @brief Pack a encapsulated_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seqnr,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -} - -/** - * @brief Encode a encapsulated_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param encapsulated_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) -{ - return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data); -} - -/** - * @brief Encode a encapsulated_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param encapsulated_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_encapsulated_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) -{ - return mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, chan, msg, encapsulated_data->seqnr, encapsulated_data->data); -} - -/** - * @brief Send a encapsulated_data message - * @param chan MAVLink channel to send the message - * - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#endif -} - -/** - * @brief Send a encapsulated_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_encapsulated_data_send_struct(mavlink_channel_t chan, const mavlink_encapsulated_data_t* encapsulated_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_encapsulated_data_send(chan, encapsulated_data->seqnr, encapsulated_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)encapsulated_data, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_encapsulated_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#else - mavlink_encapsulated_data_t *packet = (mavlink_encapsulated_data_t *)msgbuf; - 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, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ENCAPSULATED_DATA UNPACKING - - -/** - * @brief Get field seqnr from encapsulated_data message - * - * @return sequence number (starting with 0 on every transmission) - */ -static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field data from encapsulated_data message - * - * @return image data bytes - */ -static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 253, 2); -} - -/** - * @brief Decode a encapsulated_data message into a struct - * - * @param msg The message to decode - * @param encapsulated_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg); - mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN? msg->len : MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN; - memset(encapsulated_data, 0, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); - memcpy(encapsulated_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_estimator_status.h b/include/mavlink/v2.0/common/mavlink_msg_estimator_status.h deleted file mode 100644 index 2b7c6c0..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_estimator_status.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE ESTIMATOR_STATUS PACKING - -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS 230 - -MAVPACKED( -typedef struct __mavlink_estimator_status_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float vel_ratio; /*< Velocity innovation test ratio*/ - float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/ - float pos_vert_ratio; /*< Vertical position innovation test ratio*/ - float mag_ratio; /*< Magnetometer innovation test ratio*/ - float hagl_ratio; /*< Height above terrain innovation test ratio*/ - float tas_ratio; /*< True airspeed innovation test ratio*/ - float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/ - float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/ - uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/ -}) mavlink_estimator_status_t; - -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN 42 -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN 42 -#define MAVLINK_MSG_ID_230_LEN 42 -#define MAVLINK_MSG_ID_230_MIN_LEN 42 - -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC 163 -#define MAVLINK_MSG_ID_230_CRC 163 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS { \ - 230, \ - "ESTIMATOR_STATUS", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \ - { "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \ - { "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \ - { "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \ - { "mag_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_estimator_status_t, mag_ratio) }, \ - { "hagl_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_estimator_status_t, hagl_ratio) }, \ - { "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \ - { "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \ - { "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS { \ - "ESTIMATOR_STATUS", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \ - { "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \ - { "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \ - { "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \ - { "mag_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_estimator_status_t, mag_ratio) }, \ - { "hagl_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_estimator_status_t, hagl_ratio) }, \ - { "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \ - { "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \ - { "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ - } \ -} -#endif - -/** - * @brief Pack a estimator_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 time_usec Timestamp (micros since boot or Unix epoch) - * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) - * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_estimator_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#else - mavlink_estimator_status_t packet; - packet.time_usec = time_usec; - packet.vel_ratio = vel_ratio; - packet.pos_horiz_ratio = pos_horiz_ratio; - packet.pos_vert_ratio = pos_vert_ratio; - packet.mag_ratio = mag_ratio; - packet.hagl_ratio = hagl_ratio; - packet.tas_ratio = tas_ratio; - packet.pos_horiz_accuracy = pos_horiz_accuracy; - packet.pos_vert_accuracy = pos_vert_accuracy; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ESTIMATOR_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -} - -/** - * @brief Pack a estimator_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) - * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_estimator_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint16_t flags,float vel_ratio,float pos_horiz_ratio,float pos_vert_ratio,float mag_ratio,float hagl_ratio,float tas_ratio,float pos_horiz_accuracy,float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#else - mavlink_estimator_status_t packet; - packet.time_usec = time_usec; - packet.vel_ratio = vel_ratio; - packet.pos_horiz_ratio = pos_horiz_ratio; - packet.pos_vert_ratio = pos_vert_ratio; - packet.mag_ratio = mag_ratio; - packet.hagl_ratio = hagl_ratio; - packet.tas_ratio = tas_ratio; - packet.pos_horiz_accuracy = pos_horiz_accuracy; - packet.pos_vert_accuracy = pos_vert_accuracy; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ESTIMATOR_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -} - -/** - * @brief Encode a estimator_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param estimator_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_estimator_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_estimator_status_t* estimator_status) -{ - return mavlink_msg_estimator_status_pack(system_id, component_id, msg, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); -} - -/** - * @brief Encode a estimator_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param estimator_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_estimator_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_estimator_status_t* estimator_status) -{ - return mavlink_msg_estimator_status_pack_chan(system_id, component_id, chan, msg, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); -} - -/** - * @brief Send a estimator_status message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) - * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_estimator_status_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#else - mavlink_estimator_status_t packet; - packet.time_usec = time_usec; - packet.vel_ratio = vel_ratio; - packet.pos_horiz_ratio = pos_horiz_ratio; - packet.pos_vert_ratio = pos_vert_ratio; - packet.mag_ratio = mag_ratio; - packet.hagl_ratio = hagl_ratio; - packet.tas_ratio = tas_ratio; - packet.pos_horiz_accuracy = pos_horiz_accuracy; - packet.pos_vert_accuracy = pos_vert_accuracy; - packet.flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#endif -} - -/** - * @brief Send a estimator_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_estimator_status_send_struct(mavlink_channel_t chan, const mavlink_estimator_status_t* estimator_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_estimator_status_send(chan, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)estimator_status, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_estimator_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#else - mavlink_estimator_status_t *packet = (mavlink_estimator_status_t *)msgbuf; - packet->time_usec = time_usec; - packet->vel_ratio = vel_ratio; - packet->pos_horiz_ratio = pos_horiz_ratio; - packet->pos_vert_ratio = pos_vert_ratio; - packet->mag_ratio = mag_ratio; - packet->hagl_ratio = hagl_ratio; - packet->tas_ratio = tas_ratio; - packet->pos_horiz_accuracy = pos_horiz_accuracy; - packet->pos_vert_accuracy = pos_vert_accuracy; - packet->flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ESTIMATOR_STATUS UNPACKING - - -/** - * @brief Get field time_usec from estimator_status message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_estimator_status_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field flags from estimator_status message - * - * @return Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - */ -static inline uint16_t mavlink_msg_estimator_status_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 40); -} - -/** - * @brief Get field vel_ratio from estimator_status message - * - * @return Velocity innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_vel_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pos_horiz_ratio from estimator_status message - * - * @return Horizontal position innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_pos_horiz_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field pos_vert_ratio from estimator_status message - * - * @return Vertical position innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_pos_vert_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field mag_ratio from estimator_status message - * - * @return Magnetometer innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_mag_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field hagl_ratio from estimator_status message - * - * @return Height above terrain innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_hagl_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field tas_ratio from estimator_status message - * - * @return True airspeed innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_tas_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field pos_horiz_accuracy from estimator_status message - * - * @return Horizontal position 1-STD accuracy relative to the EKF local origin (m) - */ -static inline float mavlink_msg_estimator_status_get_pos_horiz_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field pos_vert_accuracy from estimator_status message - * - * @return Vertical position 1-STD accuracy relative to the EKF local origin (m) - */ -static inline float mavlink_msg_estimator_status_get_pos_vert_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a estimator_status message into a struct - * - * @param msg The message to decode - * @param estimator_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_estimator_status_decode(const mavlink_message_t* msg, mavlink_estimator_status_t* estimator_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - estimator_status->time_usec = mavlink_msg_estimator_status_get_time_usec(msg); - estimator_status->vel_ratio = mavlink_msg_estimator_status_get_vel_ratio(msg); - estimator_status->pos_horiz_ratio = mavlink_msg_estimator_status_get_pos_horiz_ratio(msg); - estimator_status->pos_vert_ratio = mavlink_msg_estimator_status_get_pos_vert_ratio(msg); - estimator_status->mag_ratio = mavlink_msg_estimator_status_get_mag_ratio(msg); - estimator_status->hagl_ratio = mavlink_msg_estimator_status_get_hagl_ratio(msg); - estimator_status->tas_ratio = mavlink_msg_estimator_status_get_tas_ratio(msg); - estimator_status->pos_horiz_accuracy = mavlink_msg_estimator_status_get_pos_horiz_accuracy(msg); - estimator_status->pos_vert_accuracy = mavlink_msg_estimator_status_get_pos_vert_accuracy(msg); - estimator_status->flags = mavlink_msg_estimator_status_get_flags(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN; - memset(estimator_status, 0, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); - memcpy(estimator_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_extended_sys_state.h b/include/mavlink/v2.0/common/mavlink_msg_extended_sys_state.h deleted file mode 100644 index 329a774..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_extended_sys_state.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE EXTENDED_SYS_STATE PACKING - -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE 245 - -MAVPACKED( -typedef struct __mavlink_extended_sys_state_t { - uint8_t vtol_state; /*< The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.*/ - uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ -}) mavlink_extended_sys_state_t; - -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN 2 -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN 2 -#define MAVLINK_MSG_ID_245_LEN 2 -#define MAVLINK_MSG_ID_245_MIN_LEN 2 - -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC 130 -#define MAVLINK_MSG_ID_245_CRC 130 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE { \ - 245, \ - "EXTENDED_SYS_STATE", \ - 2, \ - { { "vtol_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_sys_state_t, vtol_state) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_sys_state_t, landed_state) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE { \ - "EXTENDED_SYS_STATE", \ - 2, \ - { { "vtol_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_sys_state_t, vtol_state) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_sys_state_t, landed_state) }, \ - } \ -} -#endif - -/** - * @brief Pack a extended_sys_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 vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_extended_sys_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t vtol_state, uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#else - mavlink_extended_sys_state_t packet; - packet.vtol_state = vtol_state; - packet.landed_state = landed_state; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -} - -/** - * @brief Pack a extended_sys_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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_extended_sys_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t vtol_state,uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#else - mavlink_extended_sys_state_t packet; - packet.vtol_state = vtol_state; - packet.landed_state = landed_state; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -} - -/** - * @brief Encode a extended_sys_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param extended_sys_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_extended_sys_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state) -{ - return mavlink_msg_extended_sys_state_pack(system_id, component_id, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state); -} - -/** - * @brief Encode a extended_sys_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param extended_sys_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_extended_sys_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state) -{ - return mavlink_msg_extended_sys_state_pack_chan(system_id, component_id, chan, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state); -} - -/** - * @brief Send a extended_sys_state message - * @param chan MAVLink channel to send the message - * - * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_extended_sys_state_send(mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#else - mavlink_extended_sys_state_t packet; - packet.vtol_state = vtol_state; - packet.landed_state = landed_state; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)&packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#endif -} - -/** - * @brief Send a extended_sys_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_extended_sys_state_send_struct(mavlink_channel_t chan, const mavlink_extended_sys_state_t* extended_sys_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_extended_sys_state_send(chan, extended_sys_state->vtol_state, extended_sys_state->landed_state); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)extended_sys_state, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_extended_sys_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#else - mavlink_extended_sys_state_t *packet = (mavlink_extended_sys_state_t *)msgbuf; - packet->vtol_state = vtol_state; - packet->landed_state = landed_state; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE EXTENDED_SYS_STATE UNPACKING - - -/** - * @brief Get field vtol_state from extended_sys_state message - * - * @return The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - */ -static inline uint8_t mavlink_msg_extended_sys_state_get_vtol_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field landed_state from extended_sys_state message - * - * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - */ -static inline uint8_t mavlink_msg_extended_sys_state_get_landed_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a extended_sys_state message into a struct - * - * @param msg The message to decode - * @param extended_sys_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_extended_sys_state_decode(const mavlink_message_t* msg, mavlink_extended_sys_state_t* extended_sys_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - extended_sys_state->vtol_state = mavlink_msg_extended_sys_state_get_vtol_state(msg); - extended_sys_state->landed_state = mavlink_msg_extended_sys_state_get_landed_state(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN? msg->len : MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN; - memset(extended_sys_state, 0, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); - memcpy(extended_sys_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_file_transfer_protocol.h b/include/mavlink/v2.0/common/mavlink_msg_file_transfer_protocol.h deleted file mode 100644 index 07b5a3e..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_file_transfer_protocol.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE FILE_TRANSFER_PROTOCOL PACKING - -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 110 - -MAVPACKED( -typedef struct __mavlink_file_transfer_protocol_t { - uint8_t target_network; /*< Network ID (0 for broadcast)*/ - uint8_t target_system; /*< System ID (0 for broadcast)*/ - uint8_t target_component; /*< Component ID (0 for broadcast)*/ - uint8_t payload[251]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/ -}) mavlink_file_transfer_protocol_t; - -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254 -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN 254 -#define MAVLINK_MSG_ID_110_LEN 254 -#define MAVLINK_MSG_ID_110_MIN_LEN 254 - -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC 84 -#define MAVLINK_MSG_ID_110_CRC 84 - -#define MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN 251 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL { \ - 110, \ - "FILE_TRANSFER_PROTOCOL", \ - 4, \ - { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL { \ - "FILE_TRANSFER_PROTOCOL", \ - 4, \ - { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \ - } \ -} -#endif - -/** - * @brief Pack a file_transfer_protocol message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#else - mavlink_file_transfer_protocol_t packet; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -} - -/** - * @brief Pack a file_transfer_protocol message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_network,uint8_t target_system,uint8_t target_component,const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#else - mavlink_file_transfer_protocol_t packet; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -} - -/** - * @brief Encode a file_transfer_protocol struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param file_transfer_protocol C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ - return mavlink_msg_file_transfer_protocol_pack(system_id, component_id, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); -} - -/** - * @brief Encode a file_transfer_protocol struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param file_transfer_protocol C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ - return mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, chan, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); -} - -/** - * @brief Send a file_transfer_protocol message - * @param chan MAVLink channel to send the message - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_file_transfer_protocol_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#else - mavlink_file_transfer_protocol_t packet; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#endif -} - -/** - * @brief Send a file_transfer_protocol message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_file_transfer_protocol_send_struct(mavlink_channel_t chan, const mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_file_transfer_protocol_send(chan, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)file_transfer_protocol, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_file_transfer_protocol_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#else - mavlink_file_transfer_protocol_t *packet = (mavlink_file_transfer_protocol_t *)msgbuf; - packet->target_network = target_network; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE FILE_TRANSFER_PROTOCOL UNPACKING - - -/** - * @brief Get field target_network from file_transfer_protocol message - * - * @return Network ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_network(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_system from file_transfer_protocol message - * - * @return System ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field target_component from file_transfer_protocol message - * - * @return Component ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field payload from file_transfer_protocol message - * - * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_get_payload(const mavlink_message_t* msg, uint8_t *payload) -{ - return _MAV_RETURN_uint8_t_array(msg, payload, 251, 3); -} - -/** - * @brief Decode a file_transfer_protocol message into a struct - * - * @param msg The message to decode - * @param file_transfer_protocol C-struct to decode the message contents into - */ -static inline void mavlink_msg_file_transfer_protocol_decode(const mavlink_message_t* msg, mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - file_transfer_protocol->target_network = mavlink_msg_file_transfer_protocol_get_target_network(msg); - file_transfer_protocol->target_system = mavlink_msg_file_transfer_protocol_get_target_system(msg); - file_transfer_protocol->target_component = mavlink_msg_file_transfer_protocol_get_target_component(msg); - mavlink_msg_file_transfer_protocol_get_payload(msg, file_transfer_protocol->payload); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN? msg->len : MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN; - memset(file_transfer_protocol, 0, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); - memcpy(file_transfer_protocol, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_flight_information.h b/include/mavlink/v2.0/common/mavlink_msg_flight_information.h deleted file mode 100644 index f8902c1..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_flight_information.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE FLIGHT_INFORMATION PACKING - -#define MAVLINK_MSG_ID_FLIGHT_INFORMATION 264 - -MAVPACKED( -typedef struct __mavlink_flight_information_t { - uint64_t arming_time_utc; /*< Timestamp at arming (microseconds since UNIX epoch) in UTC, 0 for unknown*/ - uint64_t takeoff_time_utc; /*< Timestamp at takeoff (microseconds since UNIX epoch) in UTC, 0 for unknown*/ - uint64_t flight_uuid; /*< Universally unique identifier (UUID) of flight, should correspond to name of logfiles*/ - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ -}) mavlink_flight_information_t; - -#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN 28 -#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN 28 -#define MAVLINK_MSG_ID_264_LEN 28 -#define MAVLINK_MSG_ID_264_MIN_LEN 28 - -#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC 49 -#define MAVLINK_MSG_ID_264_CRC 49 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION { \ - 264, \ - "FLIGHT_INFORMATION", \ - 4, \ - { { "arming_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_flight_information_t, arming_time_utc) }, \ - { "takeoff_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_flight_information_t, takeoff_time_utc) }, \ - { "flight_uuid", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_flight_information_t, flight_uuid) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_flight_information_t, time_boot_ms) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION { \ - "FLIGHT_INFORMATION", \ - 4, \ - { { "arming_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_flight_information_t, arming_time_utc) }, \ - { "takeoff_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_flight_information_t, takeoff_time_utc) }, \ - { "flight_uuid", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_flight_information_t, flight_uuid) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_flight_information_t, time_boot_ms) }, \ - } \ -} -#endif - -/** - * @brief Pack a flight_information 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_boot_ms Timestamp (milliseconds since system boot) - * @param arming_time_utc Timestamp at arming (microseconds since UNIX epoch) in UTC, 0 for unknown - * @param takeoff_time_utc Timestamp at takeoff (microseconds since UNIX epoch) in UTC, 0 for unknown - * @param flight_uuid Universally unique identifier (UUID) of flight, should correspond to name of logfiles - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flight_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN]; - _mav_put_uint64_t(buf, 0, arming_time_utc); - _mav_put_uint64_t(buf, 8, takeoff_time_utc); - _mav_put_uint64_t(buf, 16, flight_uuid); - _mav_put_uint32_t(buf, 24, time_boot_ms); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN); -#else - mavlink_flight_information_t packet; - packet.arming_time_utc = arming_time_utc; - packet.takeoff_time_utc = takeoff_time_utc; - packet.flight_uuid = flight_uuid; - packet.time_boot_ms = time_boot_ms; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLIGHT_INFORMATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -} - -/** - * @brief Pack a flight_information message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param arming_time_utc Timestamp at arming (microseconds since UNIX epoch) in UTC, 0 for unknown - * @param takeoff_time_utc Timestamp at takeoff (microseconds since UNIX epoch) in UTC, 0 for unknown - * @param flight_uuid Universally unique identifier (UUID) of flight, should correspond to name of logfiles - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flight_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint64_t arming_time_utc,uint64_t takeoff_time_utc,uint64_t flight_uuid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN]; - _mav_put_uint64_t(buf, 0, arming_time_utc); - _mav_put_uint64_t(buf, 8, takeoff_time_utc); - _mav_put_uint64_t(buf, 16, flight_uuid); - _mav_put_uint32_t(buf, 24, time_boot_ms); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN); -#else - mavlink_flight_information_t packet; - packet.arming_time_utc = arming_time_utc; - packet.takeoff_time_utc = takeoff_time_utc; - packet.flight_uuid = flight_uuid; - packet.time_boot_ms = time_boot_ms; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLIGHT_INFORMATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -} - -/** - * @brief Encode a flight_information struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param flight_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flight_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flight_information_t* flight_information) -{ - return mavlink_msg_flight_information_pack(system_id, component_id, msg, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid); -} - -/** - * @brief Encode a flight_information struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flight_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flight_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flight_information_t* flight_information) -{ - return mavlink_msg_flight_information_pack_chan(system_id, component_id, chan, msg, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid); -} - -/** - * @brief Send a flight_information message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param arming_time_utc Timestamp at arming (microseconds since UNIX epoch) in UTC, 0 for unknown - * @param takeoff_time_utc Timestamp at takeoff (microseconds since UNIX epoch) in UTC, 0 for unknown - * @param flight_uuid Universally unique identifier (UUID) of flight, should correspond to name of logfiles - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_flight_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN]; - _mav_put_uint64_t(buf, 0, arming_time_utc); - _mav_put_uint64_t(buf, 8, takeoff_time_utc); - _mav_put_uint64_t(buf, 16, flight_uuid); - _mav_put_uint32_t(buf, 24, time_boot_ms); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -#else - mavlink_flight_information_t packet; - packet.arming_time_utc = arming_time_utc; - packet.takeoff_time_utc = takeoff_time_utc; - packet.flight_uuid = flight_uuid; - packet.time_boot_ms = time_boot_ms; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -#endif -} - -/** - * @brief Send a flight_information message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_flight_information_send_struct(mavlink_channel_t chan, const mavlink_flight_information_t* flight_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_flight_information_send(chan, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)flight_information, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_flight_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, arming_time_utc); - _mav_put_uint64_t(buf, 8, takeoff_time_utc); - _mav_put_uint64_t(buf, 16, flight_uuid); - _mav_put_uint32_t(buf, 24, time_boot_ms); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -#else - mavlink_flight_information_t *packet = (mavlink_flight_information_t *)msgbuf; - packet->arming_time_utc = arming_time_utc; - packet->takeoff_time_utc = takeoff_time_utc; - packet->flight_uuid = flight_uuid; - packet->time_boot_ms = time_boot_ms; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE FLIGHT_INFORMATION UNPACKING - - -/** - * @brief Get field time_boot_ms from flight_information message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_flight_information_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 24); -} - -/** - * @brief Get field arming_time_utc from flight_information message - * - * @return Timestamp at arming (microseconds since UNIX epoch) in UTC, 0 for unknown - */ -static inline uint64_t mavlink_msg_flight_information_get_arming_time_utc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field takeoff_time_utc from flight_information message - * - * @return Timestamp at takeoff (microseconds since UNIX epoch) in UTC, 0 for unknown - */ -static inline uint64_t mavlink_msg_flight_information_get_takeoff_time_utc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Get field flight_uuid from flight_information message - * - * @return Universally unique identifier (UUID) of flight, should correspond to name of logfiles - */ -static inline uint64_t mavlink_msg_flight_information_get_flight_uuid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 16); -} - -/** - * @brief Decode a flight_information message into a struct - * - * @param msg The message to decode - * @param flight_information C-struct to decode the message contents into - */ -static inline void mavlink_msg_flight_information_decode(const mavlink_message_t* msg, mavlink_flight_information_t* flight_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - flight_information->arming_time_utc = mavlink_msg_flight_information_get_arming_time_utc(msg); - flight_information->takeoff_time_utc = mavlink_msg_flight_information_get_takeoff_time_utc(msg); - flight_information->flight_uuid = mavlink_msg_flight_information_get_flight_uuid(msg); - flight_information->time_boot_ms = mavlink_msg_flight_information_get_time_boot_ms(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN; - memset(flight_information, 0, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN); - memcpy(flight_information, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_follow_target.h b/include/mavlink/v2.0/common/mavlink_msg_follow_target.h deleted file mode 100644 index bfd45f6..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_follow_target.h +++ /dev/null @@ -1,459 +0,0 @@ -#pragma once -// MESSAGE FOLLOW_TARGET PACKING - -#define MAVLINK_MSG_ID_FOLLOW_TARGET 144 - -MAVPACKED( -typedef struct __mavlink_follow_target_t { - uint64_t timestamp; /*< Timestamp in milliseconds since system boot*/ - uint64_t custom_state; /*< button states or switches of a tracker device*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - float alt; /*< AMSL, in meters*/ - float vel[3]; /*< target velocity (0,0,0) for unknown*/ - float acc[3]; /*< linear target acceleration (0,0,0) for unknown*/ - float attitude_q[4]; /*< (1 0 0 0 for unknown)*/ - float rates[3]; /*< (0 0 0 for unknown)*/ - float position_cov[3]; /*< eph epv*/ - uint8_t est_capabilities; /*< bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)*/ -}) mavlink_follow_target_t; - -#define MAVLINK_MSG_ID_FOLLOW_TARGET_LEN 93 -#define MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN 93 -#define MAVLINK_MSG_ID_144_LEN 93 -#define MAVLINK_MSG_ID_144_MIN_LEN 93 - -#define MAVLINK_MSG_ID_FOLLOW_TARGET_CRC 127 -#define MAVLINK_MSG_ID_144_CRC 127 - -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_VEL_LEN 3 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ACC_LEN 3 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ATTITUDE_Q_LEN 4 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_RATES_LEN 3 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_POSITION_COV_LEN 3 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_FOLLOW_TARGET { \ - 144, \ - "FOLLOW_TARGET", \ - 11, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \ - { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \ - { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_follow_target_t, vel) }, \ - { "acc", NULL, MAVLINK_TYPE_FLOAT, 3, 40, offsetof(mavlink_follow_target_t, acc) }, \ - { "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \ - { "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \ - { "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \ - { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_FOLLOW_TARGET { \ - "FOLLOW_TARGET", \ - 11, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \ - { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \ - { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_follow_target_t, vel) }, \ - { "acc", NULL, MAVLINK_TYPE_FLOAT, 3, 40, offsetof(mavlink_follow_target_t, acc) }, \ - { "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \ - { "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \ - { "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \ - { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ - } \ -} -#endif - -/** - * @brief Pack a follow_target message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param timestamp Timestamp in milliseconds since system boot - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt AMSL, in meters - * @param vel target velocity (0,0,0) for unknown - * @param acc linear target acceleration (0,0,0) for unknown - * @param attitude_q (1 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_follow_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#else - mavlink_follow_target_t packet; - packet.timestamp = timestamp; - packet.custom_state = custom_state; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.est_capabilities = est_capabilities; - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - mav_array_memcpy(packet.acc, acc, sizeof(float)*3); - mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet.rates, rates, sizeof(float)*3); - mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FOLLOW_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -} - -/** - * @brief Pack a follow_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param timestamp Timestamp in milliseconds since system boot - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt AMSL, in meters - * @param vel target velocity (0,0,0) for unknown - * @param acc linear target acceleration (0,0,0) for unknown - * @param attitude_q (1 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_follow_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t timestamp,uint8_t est_capabilities,int32_t lat,int32_t lon,float alt,const float *vel,const float *acc,const float *attitude_q,const float *rates,const float *position_cov,uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#else - mavlink_follow_target_t packet; - packet.timestamp = timestamp; - packet.custom_state = custom_state; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.est_capabilities = est_capabilities; - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - mav_array_memcpy(packet.acc, acc, sizeof(float)*3); - mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet.rates, rates, sizeof(float)*3); - mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FOLLOW_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -} - -/** - * @brief Encode a follow_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param follow_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_follow_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_follow_target_t* follow_target) -{ - return mavlink_msg_follow_target_pack(system_id, component_id, msg, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); -} - -/** - * @brief Encode a follow_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param follow_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_follow_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_follow_target_t* follow_target) -{ - return mavlink_msg_follow_target_pack_chan(system_id, component_id, chan, msg, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); -} - -/** - * @brief Send a follow_target message - * @param chan MAVLink channel to send the message - * - * @param timestamp Timestamp in milliseconds since system boot - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt AMSL, in meters - * @param vel target velocity (0,0,0) for unknown - * @param acc linear target acceleration (0,0,0) for unknown - * @param attitude_q (1 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_follow_target_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#else - mavlink_follow_target_t packet; - packet.timestamp = timestamp; - packet.custom_state = custom_state; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.est_capabilities = est_capabilities; - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - mav_array_memcpy(packet.acc, acc, sizeof(float)*3); - mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet.rates, rates, sizeof(float)*3); - mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)&packet, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#endif -} - -/** - * @brief Send a follow_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_follow_target_send_struct(mavlink_channel_t chan, const mavlink_follow_target_t* follow_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_follow_target_send(chan, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)follow_target, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_FOLLOW_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_follow_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#else - mavlink_follow_target_t *packet = (mavlink_follow_target_t *)msgbuf; - packet->timestamp = timestamp; - packet->custom_state = custom_state; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->est_capabilities = est_capabilities; - mav_array_memcpy(packet->vel, vel, sizeof(float)*3); - mav_array_memcpy(packet->acc, acc, sizeof(float)*3); - mav_array_memcpy(packet->attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet->rates, rates, sizeof(float)*3); - mav_array_memcpy(packet->position_cov, position_cov, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)packet, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE FOLLOW_TARGET UNPACKING - - -/** - * @brief Get field timestamp from follow_target message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint64_t mavlink_msg_follow_target_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field est_capabilities from follow_target message - * - * @return bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - */ -static inline uint8_t mavlink_msg_follow_target_get_est_capabilities(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 92); -} - -/** - * @brief Get field lat from follow_target message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_follow_target_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field lon from follow_target message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_follow_target_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field alt from follow_target message - * - * @return AMSL, in meters - */ -static inline float mavlink_msg_follow_target_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vel from follow_target message - * - * @return target velocity (0,0,0) for unknown - */ -static inline uint16_t mavlink_msg_follow_target_get_vel(const mavlink_message_t* msg, float *vel) -{ - return _MAV_RETURN_float_array(msg, vel, 3, 28); -} - -/** - * @brief Get field acc from follow_target message - * - * @return linear target acceleration (0,0,0) for unknown - */ -static inline uint16_t mavlink_msg_follow_target_get_acc(const mavlink_message_t* msg, float *acc) -{ - return _MAV_RETURN_float_array(msg, acc, 3, 40); -} - -/** - * @brief Get field attitude_q from follow_target message - * - * @return (1 0 0 0 for unknown) - */ -static inline uint16_t mavlink_msg_follow_target_get_attitude_q(const mavlink_message_t* msg, float *attitude_q) -{ - return _MAV_RETURN_float_array(msg, attitude_q, 4, 52); -} - -/** - * @brief Get field rates from follow_target message - * - * @return (0 0 0 for unknown) - */ -static inline uint16_t mavlink_msg_follow_target_get_rates(const mavlink_message_t* msg, float *rates) -{ - return _MAV_RETURN_float_array(msg, rates, 3, 68); -} - -/** - * @brief Get field position_cov from follow_target message - * - * @return eph epv - */ -static inline uint16_t mavlink_msg_follow_target_get_position_cov(const mavlink_message_t* msg, float *position_cov) -{ - return _MAV_RETURN_float_array(msg, position_cov, 3, 80); -} - -/** - * @brief Get field custom_state from follow_target message - * - * @return button states or switches of a tracker device - */ -static inline uint64_t mavlink_msg_follow_target_get_custom_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Decode a follow_target message into a struct - * - * @param msg The message to decode - * @param follow_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_follow_target_decode(const mavlink_message_t* msg, mavlink_follow_target_t* follow_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - follow_target->timestamp = mavlink_msg_follow_target_get_timestamp(msg); - follow_target->custom_state = mavlink_msg_follow_target_get_custom_state(msg); - follow_target->lat = mavlink_msg_follow_target_get_lat(msg); - follow_target->lon = mavlink_msg_follow_target_get_lon(msg); - follow_target->alt = mavlink_msg_follow_target_get_alt(msg); - mavlink_msg_follow_target_get_vel(msg, follow_target->vel); - mavlink_msg_follow_target_get_acc(msg, follow_target->acc); - mavlink_msg_follow_target_get_attitude_q(msg, follow_target->attitude_q); - mavlink_msg_follow_target_get_rates(msg, follow_target->rates); - mavlink_msg_follow_target_get_position_cov(msg, follow_target->position_cov); - follow_target->est_capabilities = mavlink_msg_follow_target_get_est_capabilities(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_FOLLOW_TARGET_LEN? msg->len : MAVLINK_MSG_ID_FOLLOW_TARGET_LEN; - memset(follow_target, 0, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); - memcpy(follow_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_global_position_int.h b/include/mavlink/v2.0/common/mavlink_msg_global_position_int.h deleted file mode 100644 index ef6267d..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_global_position_int.h +++ /dev/null @@ -1,413 +0,0 @@ -#pragma once -// MESSAGE GLOBAL_POSITION_INT PACKING - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 - -MAVPACKED( -typedef struct __mavlink_global_position_int_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ - int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)*/ - int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/ - int16_t vx; /*< Ground X Speed (Latitude, positive north), expressed as m/s * 100*/ - int16_t vy; /*< Ground Y Speed (Longitude, positive east), expressed as m/s * 100*/ - int16_t vz; /*< Ground Z Speed (Altitude, positive down), expressed as m/s * 100*/ - uint16_t hdg; /*< Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ -}) mavlink_global_position_int_t; - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN 28 -#define MAVLINK_MSG_ID_33_LEN 28 -#define MAVLINK_MSG_ID_33_MIN_LEN 28 - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104 -#define MAVLINK_MSG_ID_33_CRC 104 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ - 33, \ - "GLOBAL_POSITION_INT", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \ - { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ - "GLOBAL_POSITION_INT", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \ - { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \ - } \ -} -#endif - -/** - * @brief Pack a global_position_int 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_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - - 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; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - - 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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -} - -/** - * @brief Pack a global_position_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - - 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; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - - 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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -} - -/** - * @brief Encode a global_position_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_position_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) -{ - return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); -} - -/** - * @brief Encode a global_position_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_position_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) -{ - return mavlink_msg_global_position_int_pack_chan(system_id, component_id, chan, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); -} - -/** - * @brief Send a global_position_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - mavlink_global_position_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#endif -} - -/** - * @brief Send a global_position_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_global_position_int_send_struct(mavlink_channel_t chan, const mavlink_global_position_int_t* global_position_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_global_position_int_send(chan, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)global_position_int, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - mavlink_global_position_int_t *packet = (mavlink_global_position_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->relative_alt = relative_alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->hdg = hdg; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_POSITION_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from global_position_int message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field lat from global_position_int message - * - * @return Latitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon from global_position_int message - * - * @return Longitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt from global_position_int message - * - * @return Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - */ -static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field relative_alt from global_position_int message - * - * @return Altitude above ground in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field vx from global_position_int message - * - * @return Ground X Speed (Latitude, positive north), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field vy from global_position_int message - * - * @return Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field vz from global_position_int message - * - * @return Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 24); -} - -/** - * @brief Get field hdg from global_position_int message - * - * @return Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Decode a global_position_int message into a struct - * - * @param msg The message to decode - * @param global_position_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg); - global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg); - global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg); - global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg); - global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg); - global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg); - global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN; - memset(global_position_int, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); - memcpy(global_position_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_global_position_int_cov.h b/include/mavlink/v2.0/common/mavlink_msg_global_position_int_cov.h deleted file mode 100644 index 0d33faf..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_global_position_int_cov.h +++ /dev/null @@ -1,430 +0,0 @@ -#pragma once -// MESSAGE GLOBAL_POSITION_INT_COV PACKING - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63 - -MAVPACKED( -typedef struct __mavlink_global_position_int_cov_t { - uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/ - int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ - int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), above MSL*/ - int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/ - float vx; /*< Ground X Speed (Latitude), expressed as m/s*/ - float vy; /*< Ground Y Speed (Longitude), expressed as m/s*/ - float vz; /*< Ground Z Speed (Altitude), expressed as m/s*/ - float covariance[36]; /*< Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)*/ - uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ -}) mavlink_global_position_int_cov_t; - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 181 -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN 181 -#define MAVLINK_MSG_ID_63_LEN 181 -#define MAVLINK_MSG_ID_63_MIN_LEN 181 - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 119 -#define MAVLINK_MSG_ID_63_CRC 119 - -#define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \ - 63, \ - "GLOBAL_POSITION_INT_COV", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_int_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \ - "GLOBAL_POSITION_INT_COV", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_int_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a global_position_int_cov 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 since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s - * @param vy Ground Y Speed (Longitude), expressed as m/s - * @param vz Ground Z Speed (Altitude), expressed as m/s - * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#else - mavlink_global_position_int_cov_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -} - -/** - * @brief Pack a global_position_int_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s - * @param vy Ground Y Speed (Longitude), expressed as m/s - * @param vz Ground Z Speed (Altitude), expressed as m/s - * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t estimator_type,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,float vx,float vy,float vz,const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#else - mavlink_global_position_int_cov_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -} - -/** - * @brief Encode a global_position_int_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_position_int_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov) -{ - return mavlink_msg_global_position_int_cov_pack(system_id, component_id, msg, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); -} - -/** - * @brief Encode a global_position_int_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_position_int_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov) -{ - return mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, chan, msg, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); -} - -/** - * @brief Send a global_position_int_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat Latitude, expressed as degrees * 1E7 - * @param lon Longitude, expressed as degrees * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s - * @param vy Ground Y Speed (Longitude), expressed as m/s - * @param vz Ground Z Speed (Altitude), expressed as m/s - * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_global_position_int_cov_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#else - mavlink_global_position_int_cov_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#endif -} - -/** - * @brief Send a global_position_int_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_global_position_int_cov_send_struct(mavlink_channel_t chan, const mavlink_global_position_int_cov_t* global_position_int_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_global_position_int_cov_send(chan, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)global_position_int_cov, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#else - mavlink_global_position_int_cov_t *packet = (mavlink_global_position_int_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->relative_alt = relative_alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->estimator_type = estimator_type; - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_POSITION_INT_COV UNPACKING - - -/** - * @brief Get field time_usec from global_position_int_cov message - * - * @return Timestamp (microseconds since system boot or since UNIX epoch) - */ -static inline uint64_t mavlink_msg_global_position_int_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field estimator_type from global_position_int_cov message - * - * @return Class id of the estimator this estimate originated from. - */ -static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 180); -} - -/** - * @brief Get field lat from global_position_int_cov message - * - * @return Latitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from global_position_int_cov message - * - * @return Longitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from global_position_int_cov message - * - * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field relative_alt from global_position_int_cov message - * - * @return Altitude above ground in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field vx from global_position_int_cov message - * - * @return Ground X Speed (Latitude), expressed as m/s - */ -static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vy from global_position_int_cov message - * - * @return Ground Y Speed (Longitude), expressed as m/s - */ -static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field vz from global_position_int_cov message - * - * @return Ground Z Speed (Altitude), expressed as m/s - */ -static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field covariance from global_position_int_cov message - * - * @return Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) - */ -static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 36, 36); -} - -/** - * @brief Decode a global_position_int_cov message into a struct - * - * @param msg The message to decode - * @param global_position_int_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_position_int_cov_decode(const mavlink_message_t* msg, mavlink_global_position_int_cov_t* global_position_int_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - global_position_int_cov->time_usec = mavlink_msg_global_position_int_cov_get_time_usec(msg); - global_position_int_cov->lat = mavlink_msg_global_position_int_cov_get_lat(msg); - global_position_int_cov->lon = mavlink_msg_global_position_int_cov_get_lon(msg); - global_position_int_cov->alt = mavlink_msg_global_position_int_cov_get_alt(msg); - global_position_int_cov->relative_alt = mavlink_msg_global_position_int_cov_get_relative_alt(msg); - global_position_int_cov->vx = mavlink_msg_global_position_int_cov_get_vx(msg); - global_position_int_cov->vy = mavlink_msg_global_position_int_cov_get_vy(msg); - global_position_int_cov->vz = mavlink_msg_global_position_int_cov_get_vz(msg); - mavlink_msg_global_position_int_cov_get_covariance(msg, global_position_int_cov->covariance); - global_position_int_cov->estimator_type = mavlink_msg_global_position_int_cov_get_estimator_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN; - memset(global_position_int_cov, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); - memcpy(global_position_int_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_global_vision_position_estimate.h b/include/mavlink/v2.0/common/mavlink_msg_global_vision_position_estimate.h deleted file mode 100644 index 6b65eb0..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_global_vision_position_estimate.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101 - -MAVPACKED( -typedef struct __mavlink_global_vision_position_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X position*/ - float y; /*< Global Y position*/ - float z; /*< Global Z position*/ - float roll; /*< Roll angle in rad*/ - float pitch; /*< Pitch angle in rad*/ - float yaw; /*< Yaw angle in rad*/ -}) mavlink_global_vision_position_estimate_t; - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32 -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN 32 -#define MAVLINK_MSG_ID_101_LEN 32 -#define MAVLINK_MSG_ID_101_MIN_LEN 32 - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102 -#define MAVLINK_MSG_ID_101_CRC 102 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ - 101, \ - "GLOBAL_VISION_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ - "GLOBAL_VISION_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a global_vision_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Pack a global_vision_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Encode a global_vision_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ - return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); -} - -/** - * @brief Encode a global_vision_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ - return mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); -} - -/** - * @brief Send a global_vision_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_global_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a global_vision_position_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_global_vision_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_global_vision_position_estimate_send(chan, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)global_vision_position_estimate, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_global_vision_position_estimate_t *packet = (mavlink_global_vision_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from global_vision_position_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from global_vision_position_estimate message - * - * @return Global X position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from global_vision_position_estimate message - * - * @return Global Y position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from global_vision_position_estimate message - * - * @return Global Z position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from global_vision_position_estimate message - * - * @return Roll angle in rad - */ -static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from global_vision_position_estimate message - * - * @return Pitch angle in rad - */ -static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from global_vision_position_estimate message - * - * @return Yaw angle in rad - */ -static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a global_vision_position_estimate message into a struct - * - * @param msg The message to decode - * @param global_vision_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - global_vision_position_estimate->usec = mavlink_msg_global_vision_position_estimate_get_usec(msg); - global_vision_position_estimate->x = mavlink_msg_global_vision_position_estimate_get_x(msg); - global_vision_position_estimate->y = mavlink_msg_global_vision_position_estimate_get_y(msg); - global_vision_position_estimate->z = mavlink_msg_global_vision_position_estimate_get_z(msg); - global_vision_position_estimate->roll = mavlink_msg_global_vision_position_estimate_get_roll(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN; - memset(global_vision_position_estimate, 0, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); - memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_gps2_raw.h b/include/mavlink/v2.0/common/mavlink_msg_gps2_raw.h deleted file mode 100644 index aeccc4e..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_gps2_raw.h +++ /dev/null @@ -1,488 +0,0 @@ -#pragma once -// MESSAGE GPS2_RAW PACKING - -#define MAVLINK_MSG_ID_GPS2_RAW 124 - -MAVPACKED( -typedef struct __mavlink_gps2_raw_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/ - uint32_t dgps_age; /*< Age of DGPS info*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/ - uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/ - uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ - uint8_t fix_type; /*< See the GPS_FIX_TYPE enum.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ - uint8_t dgps_numch; /*< Number of DGPS satellites*/ -}) mavlink_gps2_raw_t; - -#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35 -#define MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN 35 -#define MAVLINK_MSG_ID_124_LEN 35 -#define MAVLINK_MSG_ID_124_MIN_LEN 35 - -#define MAVLINK_MSG_ID_GPS2_RAW_CRC 87 -#define MAVLINK_MSG_ID_124_CRC 87 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \ - 124, \ - "GPS2_RAW", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \ - { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \ - { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \ - "GPS2_RAW", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \ - { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \ - { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps2_raw 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 since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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, uint8_t dgps_numch, uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -} - -/** - * @brief Pack a gps2_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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,uint8_t dgps_numch,uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -} - -/** - * @brief Encode a gps2_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps2_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) -{ - return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); -} - -/** - * @brief Encode a gps2_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps2_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) -{ - return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); -} - -/** - * @brief Send a gps2_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps2_raw_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, uint8_t dgps_numch, uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#endif -} - -/** - * @brief Send a gps2_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps2_raw_send_struct(mavlink_channel_t chan, const mavlink_gps2_raw_t* gps2_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps2_raw_send(chan, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)gps2_raw, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, 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, uint8_t dgps_numch, uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->dgps_age = dgps_age; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->cog = cog; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - packet->dgps_numch = dgps_numch; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS2_RAW UNPACKING - - -/** - * @brief Get field time_usec from gps2_raw message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from gps2_raw message - * - * @return See the GPS_FIX_TYPE enum. - */ -static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field lat from gps2_raw message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from gps2_raw message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from gps2_raw message - * - * @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from gps2_raw message - * - * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field epv from gps2_raw message - * - * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field vel from gps2_raw message - * - * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field cog from gps2_raw message - * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field satellites_visible from gps2_raw message - * - * @return Number of satellites visible. If unknown, set to 255 - */ -static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field dgps_numch from gps2_raw message - * - * @return Number of DGPS satellites - */ -static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field dgps_age from gps2_raw message - * - * @return Age of DGPS info - */ -static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Decode a gps2_raw message into a struct - * - * @param msg The message to decode - * @param gps2_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps2_raw->time_usec = mavlink_msg_gps2_raw_get_time_usec(msg); - gps2_raw->lat = mavlink_msg_gps2_raw_get_lat(msg); - gps2_raw->lon = mavlink_msg_gps2_raw_get_lon(msg); - gps2_raw->alt = mavlink_msg_gps2_raw_get_alt(msg); - gps2_raw->dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg); - gps2_raw->eph = mavlink_msg_gps2_raw_get_eph(msg); - gps2_raw->epv = mavlink_msg_gps2_raw_get_epv(msg); - gps2_raw->vel = mavlink_msg_gps2_raw_get_vel(msg); - gps2_raw->cog = mavlink_msg_gps2_raw_get_cog(msg); - gps2_raw->fix_type = mavlink_msg_gps2_raw_get_fix_type(msg); - gps2_raw->satellites_visible = mavlink_msg_gps2_raw_get_satellites_visible(msg); - gps2_raw->dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS2_RAW_LEN? msg->len : MAVLINK_MSG_ID_GPS2_RAW_LEN; - memset(gps2_raw, 0, MAVLINK_MSG_ID_GPS2_RAW_LEN); - memcpy(gps2_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_gps2_rtk.h b/include/mavlink/v2.0/common/mavlink_msg_gps2_rtk.h deleted file mode 100644 index e383647..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_gps2_rtk.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE GPS2_RTK PACKING - -#define MAVLINK_MSG_ID_GPS2_RTK 128 - -MAVPACKED( -typedef struct __mavlink_gps2_rtk_t { - uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/ - uint32_t tow; /*< GPS Time of Week of last baseline*/ - int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/ - int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/ - int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/ - uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ - int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ - uint16_t wn; /*< GPS Week Number of last baseline*/ - uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ - uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ - uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/ - uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ - uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/ -}) mavlink_gps2_rtk_t; - -#define MAVLINK_MSG_ID_GPS2_RTK_LEN 35 -#define MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN 35 -#define MAVLINK_MSG_ID_128_LEN 35 -#define MAVLINK_MSG_ID_128_MIN_LEN 35 - -#define MAVLINK_MSG_ID_GPS2_RTK_CRC 226 -#define MAVLINK_MSG_ID_128_CRC 226 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS2_RTK { \ - 128, \ - "GPS2_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS2_RTK { \ - "GPS2_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps2_rtk 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_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#else - mavlink_gps2_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -} - -/** - * @brief Pack a gps2_rtk message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#else - mavlink_gps2_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -} - -/** - * @brief Encode a gps2_rtk struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps2_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) -{ - return mavlink_msg_gps2_rtk_pack(system_id, component_id, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); -} - -/** - * @brief Encode a gps2_rtk struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps2_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) -{ - return mavlink_msg_gps2_rtk_pack_chan(system_id, component_id, chan, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); -} - -/** - * @brief Send a gps2_rtk message - * @param chan MAVLink channel to send the message - * - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps2_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#else - mavlink_gps2_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#endif -} - -/** - * @brief Send a gps2_rtk message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps2_rtk_send_struct(mavlink_channel_t chan, const mavlink_gps2_rtk_t* gps2_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps2_rtk_send(chan, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)gps2_rtk, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS2_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps2_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#else - mavlink_gps2_rtk_t *packet = (mavlink_gps2_rtk_t *)msgbuf; - packet->time_last_baseline_ms = time_last_baseline_ms; - packet->tow = tow; - packet->baseline_a_mm = baseline_a_mm; - packet->baseline_b_mm = baseline_b_mm; - packet->baseline_c_mm = baseline_c_mm; - packet->accuracy = accuracy; - packet->iar_num_hypotheses = iar_num_hypotheses; - packet->wn = wn; - packet->rtk_receiver_id = rtk_receiver_id; - packet->rtk_health = rtk_health; - packet->rtk_rate = rtk_rate; - packet->nsats = nsats; - packet->baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS2_RTK UNPACKING - - -/** - * @brief Get field time_last_baseline_ms from gps2_rtk message - * - * @return Time since boot of last baseline message received in ms. - */ -static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field rtk_receiver_id from gps2_rtk message - * - * @return Identification of connected RTK receiver. - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field wn from gps2_rtk message - * - * @return GPS Week Number of last baseline - */ -static inline uint16_t mavlink_msg_gps2_rtk_get_wn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field tow from gps2_rtk message - * - * @return GPS Time of Week of last baseline - */ -static inline uint32_t mavlink_msg_gps2_rtk_get_tow(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field rtk_health from gps2_rtk message - * - * @return GPS-specific health report for RTK data. - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field rtk_rate from gps2_rtk message - * - * @return Rate of baseline messages being received by GPS, in HZ - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field nsats from gps2_rtk message - * - * @return Current number of sats used for RTK calculation. - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field baseline_coords_type from gps2_rtk message - * - * @return Coordinate system of baseline. 0 == ECEF, 1 == NED - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field baseline_a_mm from gps2_rtk message - * - * @return Current baseline in ECEF x or NED north component in mm. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field baseline_b_mm from gps2_rtk message - * - * @return Current baseline in ECEF y or NED east component in mm. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field baseline_c_mm from gps2_rtk message - * - * @return Current baseline in ECEF z or NED down component in mm. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field accuracy from gps2_rtk message - * - * @return Current estimate of baseline accuracy. - */ -static inline uint32_t mavlink_msg_gps2_rtk_get_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field iar_num_hypotheses from gps2_rtk message - * - * @return Current number of integer ambiguity hypotheses. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 24); -} - -/** - * @brief Decode a gps2_rtk message into a struct - * - * @param msg The message to decode - * @param gps2_rtk C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps2_rtk_decode(const mavlink_message_t* msg, mavlink_gps2_rtk_t* gps2_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps2_rtk->time_last_baseline_ms = mavlink_msg_gps2_rtk_get_time_last_baseline_ms(msg); - gps2_rtk->tow = mavlink_msg_gps2_rtk_get_tow(msg); - gps2_rtk->baseline_a_mm = mavlink_msg_gps2_rtk_get_baseline_a_mm(msg); - gps2_rtk->baseline_b_mm = mavlink_msg_gps2_rtk_get_baseline_b_mm(msg); - gps2_rtk->baseline_c_mm = mavlink_msg_gps2_rtk_get_baseline_c_mm(msg); - gps2_rtk->accuracy = mavlink_msg_gps2_rtk_get_accuracy(msg); - gps2_rtk->iar_num_hypotheses = mavlink_msg_gps2_rtk_get_iar_num_hypotheses(msg); - gps2_rtk->wn = mavlink_msg_gps2_rtk_get_wn(msg); - gps2_rtk->rtk_receiver_id = mavlink_msg_gps2_rtk_get_rtk_receiver_id(msg); - gps2_rtk->rtk_health = mavlink_msg_gps2_rtk_get_rtk_health(msg); - gps2_rtk->rtk_rate = mavlink_msg_gps2_rtk_get_rtk_rate(msg); - gps2_rtk->nsats = mavlink_msg_gps2_rtk_get_nsats(msg); - gps2_rtk->baseline_coords_type = mavlink_msg_gps2_rtk_get_baseline_coords_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS2_RTK_LEN? msg->len : MAVLINK_MSG_ID_GPS2_RTK_LEN; - memset(gps2_rtk, 0, MAVLINK_MSG_ID_GPS2_RTK_LEN); - memcpy(gps2_rtk, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_gps_global_origin.h b/include/mavlink/v2.0/common/mavlink_msg_gps_global_origin.h deleted file mode 100644 index 3008058..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_gps_global_origin.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE GPS_GLOBAL_ORIGIN PACKING - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 - -MAVPACKED( -typedef struct __mavlink_gps_global_origin_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ -}) mavlink_gps_global_origin_t; - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN 12 -#define MAVLINK_MSG_ID_49_LEN 12 -#define MAVLINK_MSG_ID_49_MIN_LEN 12 - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39 -#define MAVLINK_MSG_ID_49_CRC 39 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ - 49, \ - "GPS_GLOBAL_ORIGIN", \ - 3, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ - "GPS_GLOBAL_ORIGIN", \ - 3, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_global_origin 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 latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (AMSL), 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[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, 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, 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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Pack a gps_global_origin message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (AMSL), 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, - mavlink_message_t* msg, - int32_t latitude,int32_t longitude,int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Encode a gps_global_origin struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) -{ - return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); -} - -/** - * @brief Encode a gps_global_origin struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) -{ - return mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, chan, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); -} - -/** - * @brief Send a gps_global_origin message - * @param chan MAVLink channel to send the message - * - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - */ -#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[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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -/** - * @brief Send a gps_global_origin message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_global_origin_send_struct(mavlink_channel_t chan, const mavlink_gps_global_origin_t* gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_global_origin_send(chan, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)gps_global_origin, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#else - mavlink_gps_global_origin_t *packet = (mavlink_gps_global_origin_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING - - -/** - * @brief Get field latitude from gps_global_origin message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from gps_global_origin message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from gps_global_origin message - * - * @return Altitude (AMSL), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Decode a gps_global_origin message into a struct - * - * @param msg The message to decode - * @param gps_global_origin C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_global_origin_t* gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_global_origin->latitude = mavlink_msg_gps_global_origin_get_latitude(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN? msg->len : MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN; - memset(gps_global_origin, 0, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); - memcpy(gps_global_origin, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_gps_inject_data.h b/include/mavlink/v2.0/common/mavlink_msg_gps_inject_data.h deleted file mode 100644 index 4fbd5fc..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_gps_inject_data.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE GPS_INJECT_DATA PACKING - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA 123 - -MAVPACKED( -typedef struct __mavlink_gps_inject_data_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t len; /*< data length*/ - uint8_t data[110]; /*< raw data (110 is enough for 12 satellites of RTCMv2)*/ -}) mavlink_gps_inject_data_t; - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113 -#define MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN 113 -#define MAVLINK_MSG_ID_123_LEN 113 -#define MAVLINK_MSG_ID_123_MIN_LEN 113 - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250 -#define MAVLINK_MSG_ID_123_CRC 250 - -#define MAVLINK_MSG_GPS_INJECT_DATA_FIELD_DATA_LEN 110 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \ - 123, \ - "GPS_INJECT_DATA", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \ - "GPS_INJECT_DATA", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_inject_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -} - -/** - * @brief Pack a gps_inject_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_inject_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t len,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -} - -/** - * @brief Encode a gps_inject_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_inject_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_inject_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) -{ - return mavlink_msg_gps_inject_data_pack(system_id, component_id, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); -} - -/** - * @brief Encode a gps_inject_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_inject_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_inject_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) -{ - return mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, chan, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); -} - -/** - * @brief Send a gps_inject_data message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_inject_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#endif -} - -/** - * @brief Send a gps_inject_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_inject_data_send_struct(mavlink_channel_t chan, const mavlink_gps_inject_data_t* gps_inject_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_inject_data_send(chan, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)gps_inject_data, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_inject_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - mavlink_gps_inject_data_t *packet = (mavlink_gps_inject_data_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_INJECT_DATA UNPACKING - - -/** - * @brief Get field target_system from gps_inject_data message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from gps_inject_data message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field len from gps_inject_data message - * - * @return data length - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field data from gps_inject_data message - * - * @return raw data (110 is enough for 12 satellites of RTCMv2) - */ -static inline uint16_t mavlink_msg_gps_inject_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 110, 3); -} - -/** - * @brief Decode a gps_inject_data message into a struct - * - * @param msg The message to decode - * @param gps_inject_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_inject_data_decode(const mavlink_message_t* msg, mavlink_gps_inject_data_t* gps_inject_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_inject_data->target_system = mavlink_msg_gps_inject_data_get_target_system(msg); - gps_inject_data->target_component = mavlink_msg_gps_inject_data_get_target_component(msg); - gps_inject_data->len = mavlink_msg_gps_inject_data_get_len(msg); - mavlink_msg_gps_inject_data_get_data(msg, gps_inject_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN? msg->len : MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN; - memset(gps_inject_data, 0, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); - memcpy(gps_inject_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_gps_input.h b/include/mavlink/v2.0/common/mavlink_msg_gps_input.h deleted file mode 100644 index 5fb9e9c..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_gps_input.h +++ /dev/null @@ -1,638 +0,0 @@ -#pragma once -// MESSAGE GPS_INPUT PACKING - -#define MAVLINK_MSG_ID_GPS_INPUT 232 - -MAVPACKED( -typedef struct __mavlink_gps_input_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - uint32_t time_week_ms; /*< GPS time (milliseconds from start of GPS week)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - float alt; /*< Altitude (AMSL, not WGS84), in m (positive for up)*/ - float hdop; /*< GPS HDOP horizontal dilution of position in m*/ - float vdop; /*< GPS VDOP vertical dilution of position in m*/ - float vn; /*< GPS velocity in m/s in NORTH direction in earth-fixed NED frame*/ - float ve; /*< GPS velocity in m/s in EAST direction in earth-fixed NED frame*/ - float vd; /*< GPS velocity in m/s in DOWN direction in earth-fixed NED frame*/ - float speed_accuracy; /*< GPS speed accuracy in m/s*/ - float horiz_accuracy; /*< GPS horizontal accuracy in m*/ - float vert_accuracy; /*< GPS vertical accuracy in m*/ - uint16_t ignore_flags; /*< Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided.*/ - uint16_t time_week; /*< GPS week number*/ - uint8_t gps_id; /*< ID of the GPS for multiple GPS inputs*/ - uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK*/ - uint8_t satellites_visible; /*< Number of satellites visible.*/ -}) mavlink_gps_input_t; - -#define MAVLINK_MSG_ID_GPS_INPUT_LEN 63 -#define MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN 63 -#define MAVLINK_MSG_ID_232_LEN 63 -#define MAVLINK_MSG_ID_232_MIN_LEN 63 - -#define MAVLINK_MSG_ID_GPS_INPUT_CRC 151 -#define MAVLINK_MSG_ID_232_CRC 151 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_INPUT { \ - 232, \ - "GPS_INPUT", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \ - { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \ - { "hdop", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_input_t, hdop) }, \ - { "vdop", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_input_t, vdop) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_input_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_input_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_input_t, vd) }, \ - { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \ - { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \ - { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \ - { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_INPUT { \ - "GPS_INPUT", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \ - { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \ - { "hdop", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_input_t, hdop) }, \ - { "vdop", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_input_t, vdop) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_input_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_input_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_input_t, vd) }, \ - { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \ - { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \ - { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \ - { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_input 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 (micros since boot or Unix epoch) - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - * @param time_week_ms GPS time (milliseconds from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in m (positive for up) - * @param hdop GPS HDOP horizontal dilution of position in m - * @param vdop GPS VDOP vertical dilution of position in m - * @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame - * @param speed_accuracy GPS speed accuracy in m/s - * @param horiz_accuracy GPS horizontal accuracy in m - * @param vert_accuracy GPS vertical accuracy in m - * @param satellites_visible Number of satellites visible. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#else - mavlink_gps_input_t packet; - packet.time_usec = time_usec; - packet.time_week_ms = time_week_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.hdop = hdop; - packet.vdop = vdop; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.speed_accuracy = speed_accuracy; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - packet.ignore_flags = ignore_flags; - packet.time_week = time_week; - packet.gps_id = gps_id; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INPUT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -} - -/** - * @brief Pack a gps_input message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - * @param time_week_ms GPS time (milliseconds from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in m (positive for up) - * @param hdop GPS HDOP horizontal dilution of position in m - * @param vdop GPS VDOP vertical dilution of position in m - * @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame - * @param speed_accuracy GPS speed accuracy in m/s - * @param horiz_accuracy GPS horizontal accuracy in m - * @param vert_accuracy GPS vertical accuracy in m - * @param satellites_visible Number of satellites visible. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_input_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t gps_id,uint16_t ignore_flags,uint32_t time_week_ms,uint16_t time_week,uint8_t fix_type,int32_t lat,int32_t lon,float alt,float hdop,float vdop,float vn,float ve,float vd,float speed_accuracy,float horiz_accuracy,float vert_accuracy,uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#else - mavlink_gps_input_t packet; - packet.time_usec = time_usec; - packet.time_week_ms = time_week_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.hdop = hdop; - packet.vdop = vdop; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.speed_accuracy = speed_accuracy; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - packet.ignore_flags = ignore_flags; - packet.time_week = time_week; - packet.gps_id = gps_id; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INPUT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -} - -/** - * @brief Encode a gps_input struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_input C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_input_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input) -{ - return mavlink_msg_gps_input_pack(system_id, component_id, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible); -} - -/** - * @brief Encode a gps_input struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_input C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_input_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input) -{ - return mavlink_msg_gps_input_pack_chan(system_id, component_id, chan, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible); -} - -/** - * @brief Send a gps_input message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - * @param time_week_ms GPS time (milliseconds from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in m (positive for up) - * @param hdop GPS HDOP horizontal dilution of position in m - * @param vdop GPS VDOP vertical dilution of position in m - * @param vn GPS velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in m/s in DOWN direction in earth-fixed NED frame - * @param speed_accuracy GPS speed accuracy in m/s - * @param horiz_accuracy GPS horizontal accuracy in m - * @param vert_accuracy GPS vertical accuracy in m - * @param satellites_visible Number of satellites visible. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_input_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#else - mavlink_gps_input_t packet; - packet.time_usec = time_usec; - packet.time_week_ms = time_week_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.hdop = hdop; - packet.vdop = vdop; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.speed_accuracy = speed_accuracy; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - packet.ignore_flags = ignore_flags; - packet.time_week = time_week; - packet.gps_id = gps_id; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)&packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#endif -} - -/** - * @brief Send a gps_input message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_input_send_struct(mavlink_channel_t chan, const mavlink_gps_input_t* gps_input) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_input_send(chan, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)gps_input, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_INPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_input_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#else - mavlink_gps_input_t *packet = (mavlink_gps_input_t *)msgbuf; - packet->time_usec = time_usec; - packet->time_week_ms = time_week_ms; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->hdop = hdop; - packet->vdop = vdop; - packet->vn = vn; - packet->ve = ve; - packet->vd = vd; - packet->speed_accuracy = speed_accuracy; - packet->horiz_accuracy = horiz_accuracy; - packet->vert_accuracy = vert_accuracy; - packet->ignore_flags = ignore_flags; - packet->time_week = time_week; - packet->gps_id = gps_id; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_INPUT UNPACKING - - -/** - * @brief Get field time_usec from gps_input message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_gps_input_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field gps_id from gps_input message - * - * @return ID of the GPS for multiple GPS inputs - */ -static inline uint8_t mavlink_msg_gps_input_get_gps_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 60); -} - -/** - * @brief Get field ignore_flags from gps_input message - * - * @return Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - */ -static inline uint16_t mavlink_msg_gps_input_get_ignore_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 56); -} - -/** - * @brief Get field time_week_ms from gps_input message - * - * @return GPS time (milliseconds from start of GPS week) - */ -static inline uint32_t mavlink_msg_gps_input_get_time_week_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field time_week from gps_input message - * - * @return GPS week number - */ -static inline uint16_t mavlink_msg_gps_input_get_time_week(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 58); -} - -/** - * @brief Get field fix_type from gps_input message - * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - */ -static inline uint8_t mavlink_msg_gps_input_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 61); -} - -/** - * @brief Get field lat from gps_input message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_input_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field lon from gps_input message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_input_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field alt from gps_input message - * - * @return Altitude (AMSL, not WGS84), in m (positive for up) - */ -static inline float mavlink_msg_gps_input_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field hdop from gps_input message - * - * @return GPS HDOP horizontal dilution of position in m - */ -static inline float mavlink_msg_gps_input_get_hdop(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vdop from gps_input message - * - * @return GPS VDOP vertical dilution of position in m - */ -static inline float mavlink_msg_gps_input_get_vdop(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field vn from gps_input message - * - * @return GPS velocity in m/s in NORTH direction in earth-fixed NED frame - */ -static inline float mavlink_msg_gps_input_get_vn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ve from gps_input message - * - * @return GPS velocity in m/s in EAST direction in earth-fixed NED frame - */ -static inline float mavlink_msg_gps_input_get_ve(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field vd from gps_input message - * - * @return GPS velocity in m/s in DOWN direction in earth-fixed NED frame - */ -static inline float mavlink_msg_gps_input_get_vd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field speed_accuracy from gps_input message - * - * @return GPS speed accuracy in m/s - */ -static inline float mavlink_msg_gps_input_get_speed_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field horiz_accuracy from gps_input message - * - * @return GPS horizontal accuracy in m - */ -static inline float mavlink_msg_gps_input_get_horiz_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field vert_accuracy from gps_input message - * - * @return GPS vertical accuracy in m - */ -static inline float mavlink_msg_gps_input_get_vert_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field satellites_visible from gps_input message - * - * @return Number of satellites visible. - */ -static inline uint8_t mavlink_msg_gps_input_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 62); -} - -/** - * @brief Decode a gps_input message into a struct - * - * @param msg The message to decode - * @param gps_input C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_input_decode(const mavlink_message_t* msg, mavlink_gps_input_t* gps_input) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_input->time_usec = mavlink_msg_gps_input_get_time_usec(msg); - gps_input->time_week_ms = mavlink_msg_gps_input_get_time_week_ms(msg); - gps_input->lat = mavlink_msg_gps_input_get_lat(msg); - gps_input->lon = mavlink_msg_gps_input_get_lon(msg); - gps_input->alt = mavlink_msg_gps_input_get_alt(msg); - gps_input->hdop = mavlink_msg_gps_input_get_hdop(msg); - gps_input->vdop = mavlink_msg_gps_input_get_vdop(msg); - gps_input->vn = mavlink_msg_gps_input_get_vn(msg); - gps_input->ve = mavlink_msg_gps_input_get_ve(msg); - gps_input->vd = mavlink_msg_gps_input_get_vd(msg); - gps_input->speed_accuracy = mavlink_msg_gps_input_get_speed_accuracy(msg); - gps_input->horiz_accuracy = mavlink_msg_gps_input_get_horiz_accuracy(msg); - gps_input->vert_accuracy = mavlink_msg_gps_input_get_vert_accuracy(msg); - gps_input->ignore_flags = mavlink_msg_gps_input_get_ignore_flags(msg); - gps_input->time_week = mavlink_msg_gps_input_get_time_week(msg); - gps_input->gps_id = mavlink_msg_gps_input_get_gps_id(msg); - gps_input->fix_type = mavlink_msg_gps_input_get_fix_type(msg); - gps_input->satellites_visible = mavlink_msg_gps_input_get_satellites_visible(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_INPUT_LEN? msg->len : MAVLINK_MSG_ID_GPS_INPUT_LEN; - memset(gps_input, 0, MAVLINK_MSG_ID_GPS_INPUT_LEN); - memcpy(gps_input, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_gps_raw_int.h b/include/mavlink/v2.0/common/mavlink_msg_gps_raw_int.h deleted file mode 100644 index 3033b6d..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_gps_raw_int.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE GPS_RAW_INT PACKING - -#define MAVLINK_MSG_ID_GPS_RAW_INT 24 - -MAVPACKED( -typedef struct __mavlink_gps_raw_int_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t alt; /*< Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/ - uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/ - uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ - uint8_t fix_type; /*< See the GPS_FIX_TYPE enum.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ -}) mavlink_gps_raw_int_t; - -#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 -#define MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN 30 -#define MAVLINK_MSG_ID_24_LEN 30 -#define MAVLINK_MSG_ID_24_MIN_LEN 30 - -#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24 -#define MAVLINK_MSG_ID_24_CRC 24 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ - 24, \ - "GPS_RAW_INT", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ - "GPS_RAW_INT", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_raw_int 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 since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - - 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; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - 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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -} - -/** - * @brief Pack a gps_raw_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - - 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; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - 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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -} - -/** - * @brief Encode a gps_raw_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_raw_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) -{ - return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); -} - -/** - * @brief Encode a gps_raw_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_raw_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) -{ - return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); -} - -/** - * @brief Send a gps_raw_int message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type See the GPS_FIX_TYPE enum. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - mavlink_gps_raw_int_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - 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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#endif -} - -/** - * @brief Send a gps_raw_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_raw_int_send_struct(mavlink_channel_t chan, const mavlink_gps_raw_int_t* gps_raw_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_raw_int_send(chan, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)gps_raw_int, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - mavlink_gps_raw_int_t *packet = (mavlink_gps_raw_int_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->cog = cog; - 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, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_RAW_INT UNPACKING - - -/** - * @brief Get field time_usec from gps_raw_int message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from gps_raw_int message - * - * @return See the GPS_FIX_TYPE enum. - */ -static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field lat from gps_raw_int message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from gps_raw_int message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from gps_raw_int message - * - * @return Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - */ -static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from gps_raw_int message - * - * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field epv from gps_raw_int message - * - * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field vel from gps_raw_int message - * - * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field cog from gps_raw_int message - * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field satellites_visible from gps_raw_int message - * - * @return Number of satellites visible. If unknown, set to 255 - */ -static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Decode a gps_raw_int message into a struct - * - * @param msg The message to decode - * @param gps_raw_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg); - gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg); - gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg); - gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg); - gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg); - gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg); - gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg); - gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(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 - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RAW_INT_LEN? msg->len : MAVLINK_MSG_ID_GPS_RAW_INT_LEN; - memset(gps_raw_int, 0, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); - memcpy(gps_raw_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_gps_rtcm_data.h b/include/mavlink/v2.0/common/mavlink_msg_gps_rtcm_data.h deleted file mode 100644 index 309a97b..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_gps_rtcm_data.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE GPS_RTCM_DATA PACKING - -#define MAVLINK_MSG_ID_GPS_RTCM_DATA 233 - -MAVPACKED( -typedef struct __mavlink_gps_rtcm_data_t { - uint8_t flags; /*< LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.*/ - uint8_t len; /*< data length*/ - uint8_t data[180]; /*< RTCM message (may be fragmented)*/ -}) mavlink_gps_rtcm_data_t; - -#define MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN 182 -#define MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN 182 -#define MAVLINK_MSG_ID_233_LEN 182 -#define MAVLINK_MSG_ID_233_MIN_LEN 182 - -#define MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC 35 -#define MAVLINK_MSG_ID_233_CRC 35 - -#define MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN 180 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA { \ - 233, \ - "GPS_RTCM_DATA", \ - 3, \ - { { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_rtcm_data_t, flags) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_rtcm_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 180, 2, offsetof(mavlink_gps_rtcm_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA { \ - "GPS_RTCM_DATA", \ - 3, \ - { { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_rtcm_data_t, flags) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_rtcm_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 180, 2, offsetof(mavlink_gps_rtcm_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_rtcm_data 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 flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - * @param len data length - * @param data RTCM message (may be fragmented) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t flags, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN]; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#else - mavlink_gps_rtcm_data_t packet; - packet.flags = flags; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTCM_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -} - -/** - * @brief Pack a gps_rtcm_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - * @param len data length - * @param data RTCM message (may be fragmented) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t flags,uint8_t len,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN]; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#else - mavlink_gps_rtcm_data_t packet; - packet.flags = flags; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTCM_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -} - -/** - * @brief Encode a gps_rtcm_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_rtcm_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ - return mavlink_msg_gps_rtcm_data_pack(system_id, component_id, msg, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data); -} - -/** - * @brief Encode a gps_rtcm_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_rtcm_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ - return mavlink_msg_gps_rtcm_data_pack_chan(system_id, component_id, chan, msg, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data); -} - -/** - * @brief Send a gps_rtcm_data message - * @param chan MAVLink channel to send the message - * - * @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - * @param len data length - * @param data RTCM message (may be fragmented) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_rtcm_data_send(mavlink_channel_t chan, uint8_t flags, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN]; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#else - mavlink_gps_rtcm_data_t packet; - packet.flags = flags; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#endif -} - -/** - * @brief Send a gps_rtcm_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_rtcm_data_send_struct(mavlink_channel_t chan, const mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_rtcm_data_send(chan, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (const char *)gps_rtcm_data, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_rtcm_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t flags, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#else - mavlink_gps_rtcm_data_t *packet = (mavlink_gps_rtcm_data_t *)msgbuf; - packet->flags = flags; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_RTCM_DATA UNPACKING - - -/** - * @brief Get field flags from gps_rtcm_data message - * - * @return LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - */ -static inline uint8_t mavlink_msg_gps_rtcm_data_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field len from gps_rtcm_data message - * - * @return data length - */ -static inline uint8_t mavlink_msg_gps_rtcm_data_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field data from gps_rtcm_data message - * - * @return RTCM message (may be fragmented) - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 180, 2); -} - -/** - * @brief Decode a gps_rtcm_data message into a struct - * - * @param msg The message to decode - * @param gps_rtcm_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_rtcm_data_decode(const mavlink_message_t* msg, mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_rtcm_data->flags = mavlink_msg_gps_rtcm_data_get_flags(msg); - gps_rtcm_data->len = mavlink_msg_gps_rtcm_data_get_len(msg); - mavlink_msg_gps_rtcm_data_get_data(msg, gps_rtcm_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN? msg->len : MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN; - memset(gps_rtcm_data, 0, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); - memcpy(gps_rtcm_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_gps_rtk.h b/include/mavlink/v2.0/common/mavlink_msg_gps_rtk.h deleted file mode 100644 index 3b25c80..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_gps_rtk.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE GPS_RTK PACKING - -#define MAVLINK_MSG_ID_GPS_RTK 127 - -MAVPACKED( -typedef struct __mavlink_gps_rtk_t { - uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/ - uint32_t tow; /*< GPS Time of Week of last baseline*/ - int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/ - int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/ - int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/ - uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ - int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ - uint16_t wn; /*< GPS Week Number of last baseline*/ - uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ - uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ - uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/ - uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ - uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/ -}) mavlink_gps_rtk_t; - -#define MAVLINK_MSG_ID_GPS_RTK_LEN 35 -#define MAVLINK_MSG_ID_GPS_RTK_MIN_LEN 35 -#define MAVLINK_MSG_ID_127_LEN 35 -#define MAVLINK_MSG_ID_127_MIN_LEN 35 - -#define MAVLINK_MSG_ID_GPS_RTK_CRC 25 -#define MAVLINK_MSG_ID_127_CRC 25 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_RTK { \ - 127, \ - "GPS_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_RTK { \ - "GPS_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_rtk 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_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); -#else - mavlink_gps_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -} - -/** - * @brief Pack a gps_rtk message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); -#else - mavlink_gps_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -} - -/** - * @brief Encode a gps_rtk struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) -{ - return mavlink_msg_gps_rtk_pack(system_id, component_id, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); -} - -/** - * @brief Encode a gps_rtk struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) -{ - return mavlink_msg_gps_rtk_pack_chan(system_id, component_id, chan, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); -} - -/** - * @brief Send a gps_rtk message - * @param chan MAVLink channel to send the message - * - * @param time_last_baseline_ms Time since boot of last baseline message received in ms. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate Rate of baseline messages being received by GPS, in HZ - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED - * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. - * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. - * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#else - mavlink_gps_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#endif -} - -/** - * @brief Send a gps_rtk message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_rtk_send_struct(mavlink_channel_t chan, const mavlink_gps_rtk_t* gps_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_rtk_send(chan, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)gps_rtk, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#else - mavlink_gps_rtk_t *packet = (mavlink_gps_rtk_t *)msgbuf; - packet->time_last_baseline_ms = time_last_baseline_ms; - packet->tow = tow; - packet->baseline_a_mm = baseline_a_mm; - packet->baseline_b_mm = baseline_b_mm; - packet->baseline_c_mm = baseline_c_mm; - packet->accuracy = accuracy; - packet->iar_num_hypotheses = iar_num_hypotheses; - packet->wn = wn; - packet->rtk_receiver_id = rtk_receiver_id; - packet->rtk_health = rtk_health; - packet->rtk_rate = rtk_rate; - packet->nsats = nsats; - packet->baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_RTK UNPACKING - - -/** - * @brief Get field time_last_baseline_ms from gps_rtk message - * - * @return Time since boot of last baseline message received in ms. - */ -static inline uint32_t mavlink_msg_gps_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field rtk_receiver_id from gps_rtk message - * - * @return Identification of connected RTK receiver. - */ -static inline uint8_t mavlink_msg_gps_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field wn from gps_rtk message - * - * @return GPS Week Number of last baseline - */ -static inline uint16_t mavlink_msg_gps_rtk_get_wn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field tow from gps_rtk message - * - * @return GPS Time of Week of last baseline - */ -static inline uint32_t mavlink_msg_gps_rtk_get_tow(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field rtk_health from gps_rtk message - * - * @return GPS-specific health report for RTK data. - */ -static inline uint8_t mavlink_msg_gps_rtk_get_rtk_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field rtk_rate from gps_rtk message - * - * @return Rate of baseline messages being received by GPS, in HZ - */ -static inline uint8_t mavlink_msg_gps_rtk_get_rtk_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field nsats from gps_rtk message - * - * @return Current number of sats used for RTK calculation. - */ -static inline uint8_t mavlink_msg_gps_rtk_get_nsats(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field baseline_coords_type from gps_rtk message - * - * @return Coordinate system of baseline. 0 == ECEF, 1 == NED - */ -static inline uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field baseline_a_mm from gps_rtk message - * - * @return Current baseline in ECEF x or NED north component in mm. - */ -static inline int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field baseline_b_mm from gps_rtk message - * - * @return Current baseline in ECEF y or NED east component in mm. - */ -static inline int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field baseline_c_mm from gps_rtk message - * - * @return Current baseline in ECEF z or NED down component in mm. - */ -static inline int32_t mavlink_msg_gps_rtk_get_baseline_c_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field accuracy from gps_rtk message - * - * @return Current estimate of baseline accuracy. - */ -static inline uint32_t mavlink_msg_gps_rtk_get_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field iar_num_hypotheses from gps_rtk message - * - * @return Current number of integer ambiguity hypotheses. - */ -static inline int32_t mavlink_msg_gps_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 24); -} - -/** - * @brief Decode a gps_rtk message into a struct - * - * @param msg The message to decode - * @param gps_rtk C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_rtk_decode(const mavlink_message_t* msg, mavlink_gps_rtk_t* gps_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_rtk->time_last_baseline_ms = mavlink_msg_gps_rtk_get_time_last_baseline_ms(msg); - gps_rtk->tow = mavlink_msg_gps_rtk_get_tow(msg); - gps_rtk->baseline_a_mm = mavlink_msg_gps_rtk_get_baseline_a_mm(msg); - gps_rtk->baseline_b_mm = mavlink_msg_gps_rtk_get_baseline_b_mm(msg); - gps_rtk->baseline_c_mm = mavlink_msg_gps_rtk_get_baseline_c_mm(msg); - gps_rtk->accuracy = mavlink_msg_gps_rtk_get_accuracy(msg); - gps_rtk->iar_num_hypotheses = mavlink_msg_gps_rtk_get_iar_num_hypotheses(msg); - gps_rtk->wn = mavlink_msg_gps_rtk_get_wn(msg); - gps_rtk->rtk_receiver_id = mavlink_msg_gps_rtk_get_rtk_receiver_id(msg); - gps_rtk->rtk_health = mavlink_msg_gps_rtk_get_rtk_health(msg); - gps_rtk->rtk_rate = mavlink_msg_gps_rtk_get_rtk_rate(msg); - gps_rtk->nsats = mavlink_msg_gps_rtk_get_nsats(msg); - gps_rtk->baseline_coords_type = mavlink_msg_gps_rtk_get_baseline_coords_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RTK_LEN? msg->len : MAVLINK_MSG_ID_GPS_RTK_LEN; - memset(gps_rtk, 0, MAVLINK_MSG_ID_GPS_RTK_LEN); - memcpy(gps_rtk, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_gps_status.h b/include/mavlink/v2.0/common/mavlink_msg_gps_status.h deleted file mode 100644 index 8511be9..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_gps_status.h +++ /dev/null @@ -1,334 +0,0 @@ -#pragma once -// MESSAGE GPS_STATUS PACKING - -#define MAVLINK_MSG_ID_GPS_STATUS 25 - -MAVPACKED( -typedef struct __mavlink_gps_status_t { - uint8_t satellites_visible; /*< Number of satellites visible*/ - uint8_t satellite_prn[20]; /*< Global satellite ID*/ - uint8_t satellite_used[20]; /*< 0: Satellite not used, 1: used for localization*/ - uint8_t satellite_elevation[20]; /*< Elevation (0: right on top of receiver, 90: on the horizon) of satellite*/ - uint8_t satellite_azimuth[20]; /*< Direction of satellite, 0: 0 deg, 255: 360 deg.*/ - uint8_t satellite_snr[20]; /*< Signal to noise ratio of satellite*/ -}) mavlink_gps_status_t; - -#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101 -#define MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN 101 -#define MAVLINK_MSG_ID_25_LEN 101 -#define MAVLINK_MSG_ID_25_MIN_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 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ - 25, \ - "GPS_STATUS", \ - 6, \ - { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ - { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ - { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ - { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ - { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ - { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ - "GPS_STATUS", \ - 6, \ - { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ - { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ - { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ - { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ - { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ - { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_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 satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - 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, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -} - -/** - * @brief Pack a gps_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - 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, 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, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -} - -/** - * @brief Encode a gps_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) -{ - return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); -} - -/** - * @brief Encode a gps_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) -{ - return mavlink_msg_gps_status_pack_chan(system_id, component_id, chan, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); -} - -/** - * @brief Send a gps_status message - * @param chan MAVLink channel to send the message - * - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - 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, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#endif -} - -/** - * @brief Send a gps_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_status_send_struct(mavlink_channel_t chan, const mavlink_gps_status_t* gps_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_status_send(chan, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)gps_status, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_status_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - mavlink_gps_status_t *packet = (mavlink_gps_status_t *)msgbuf; - packet->satellites_visible = satellites_visible; - mav_array_memcpy(packet->satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet->satellite_used, satellite_used, sizeof(uint8_t)*20); - 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, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_STATUS UNPACKING - - -/** - * @brief Get field satellites_visible from gps_status message - * - * @return Number of satellites visible - */ -static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field satellite_prn from gps_status message - * - * @return Global satellite ID - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1); -} - -/** - * @brief Get field satellite_used from gps_status message - * - * @return 0: Satellite not used, 1: used for localization - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21); -} - -/** - * @brief Get field satellite_elevation from gps_status message - * - * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41); -} - -/** - * @brief Get field satellite_azimuth from gps_status message - * - * @return Direction of satellite, 0: 0 deg, 255: 360 deg. - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61); -} - -/** - * @brief Get field satellite_snr from gps_status message - * - * @return Signal to noise ratio of satellite - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81); -} - -/** - * @brief Decode a gps_status message into a struct - * - * @param msg The message to decode - * @param gps_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg); - mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn); - mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used); - mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_GPS_STATUS_LEN; - memset(gps_status, 0, MAVLINK_MSG_ID_GPS_STATUS_LEN); - memcpy(gps_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_heartbeat.h b/include/mavlink/v2.0/common/mavlink_msg_heartbeat.h deleted file mode 100644 index 66020ff..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_heartbeat.h +++ /dev/null @@ -1,335 +0,0 @@ -#pragma once -// MESSAGE HEARTBEAT PACKING - -#define MAVLINK_MSG_ID_HEARTBEAT 0 - -MAVPACKED( -typedef struct __mavlink_heartbeat_t { - uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/ - uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)*/ - uint8_t autopilot; /*< Autopilot type / class. defined in MAV_AUTOPILOT ENUM*/ - uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/ - uint8_t system_status; /*< System status flag, see MAV_STATE ENUM*/ - uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/ -}) mavlink_heartbeat_t; - -#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 -#define MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN 9 -#define MAVLINK_MSG_ID_0_LEN 9 -#define MAVLINK_MSG_ID_0_MIN_LEN 9 - -#define MAVLINK_MSG_ID_HEARTBEAT_CRC 50 -#define MAVLINK_MSG_ID_0_CRC 50 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ - 0, \ - "HEARTBEAT", \ - 6, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ - { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ - { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ - { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ - "HEARTBEAT", \ - 6, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ - { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ - { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ - { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ - } \ -} -#endif - -/** - * @brief Pack a heartbeat message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - - 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, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -} - -/** - * @brief Pack a heartbeat message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - - 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, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -} - -/** - * @brief Encode a heartbeat struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param heartbeat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) -{ - return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); -} - -/** - * @brief Encode a heartbeat struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param heartbeat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) -{ - return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); -} - -/** - * @brief Send a heartbeat message - * @param chan MAVLink channel to send the message - * - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_uint8_t(buf, 6, base_mode); - _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, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#endif -} - -/** - * @brief Send a heartbeat message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_heartbeat_send_struct(mavlink_channel_t chan, const mavlink_heartbeat_t* heartbeat) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_heartbeat_send(chan, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)heartbeat, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 5, autopilot); - _mav_put_uint8_t(buf, 6, base_mode); - _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, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf; - packet->custom_mode = custom_mode; - packet->type = type; - packet->autopilot = autopilot; - packet->base_mode = base_mode; - packet->system_status = system_status; - packet->mavlink_version = 3; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HEARTBEAT UNPACKING - - -/** - * @brief Get field type from heartbeat message - * - * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - */ -static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field autopilot from heartbeat message - * - * @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM - */ -static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field base_mode from heartbeat message - * - * @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - */ -static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field custom_mode from heartbeat message - * - * @return A bitfield for use for autopilot-specific flags. - */ -static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field system_status from heartbeat message - * - * @return System status flag, see MAV_STATE ENUM - */ -static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field mavlink_version from heartbeat message - * - * @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version - */ -static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Decode a heartbeat message into a struct - * - * @param msg The message to decode - * @param heartbeat C-struct to decode the message contents into - */ -static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg); - heartbeat->type = mavlink_msg_heartbeat_get_type(msg); - heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); - heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg); - heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg); - heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HEARTBEAT_LEN? msg->len : MAVLINK_MSG_ID_HEARTBEAT_LEN; - memset(heartbeat, 0, MAVLINK_MSG_ID_HEARTBEAT_LEN); - memcpy(heartbeat, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_high_latency.h b/include/mavlink/v2.0/common/mavlink_msg_high_latency.h deleted file mode 100644 index 7c87e5c..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_high_latency.h +++ /dev/null @@ -1,788 +0,0 @@ -#pragma once -// MESSAGE HIGH_LATENCY PACKING - -#define MAVLINK_MSG_ID_HIGH_LATENCY 234 - -MAVPACKED( -typedef struct __mavlink_high_latency_t { - uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/ - int32_t latitude; /*< Latitude, expressed as degrees * 1E7*/ - int32_t longitude; /*< Longitude, expressed as degrees * 1E7*/ - int16_t roll; /*< roll (centidegrees)*/ - int16_t pitch; /*< pitch (centidegrees)*/ - uint16_t heading; /*< heading (centidegrees)*/ - int16_t heading_sp; /*< heading setpoint (centidegrees)*/ - int16_t altitude_amsl; /*< Altitude above mean sea level (meters)*/ - int16_t altitude_sp; /*< Altitude setpoint relative to the home position (meters)*/ - uint16_t wp_distance; /*< distance to target (meters)*/ - uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/ - uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ - int8_t throttle; /*< throttle (percentage)*/ - uint8_t airspeed; /*< airspeed (m/s)*/ - uint8_t airspeed_sp; /*< airspeed setpoint (m/s)*/ - uint8_t groundspeed; /*< groundspeed (m/s)*/ - int8_t climb_rate; /*< climb rate (m/s)*/ - uint8_t gps_nsat; /*< Number of satellites visible. If unknown, set to 255*/ - uint8_t gps_fix_type; /*< See the GPS_FIX_TYPE enum.*/ - uint8_t battery_remaining; /*< Remaining battery (percentage)*/ - int8_t temperature; /*< Autopilot temperature (degrees C)*/ - int8_t temperature_air; /*< Air temperature (degrees C) from airspeed sensor*/ - uint8_t failsafe; /*< failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)*/ - uint8_t wp_num; /*< current waypoint number*/ -}) mavlink_high_latency_t; - -#define MAVLINK_MSG_ID_HIGH_LATENCY_LEN 40 -#define MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN 40 -#define MAVLINK_MSG_ID_234_LEN 40 -#define MAVLINK_MSG_ID_234_MIN_LEN 40 - -#define MAVLINK_MSG_ID_HIGH_LATENCY_CRC 150 -#define MAVLINK_MSG_ID_234_CRC 150 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY { \ - 234, \ - "HIGH_LATENCY", \ - 24, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \ - { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \ - { "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \ - { "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \ - { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \ - { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \ - { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \ - { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \ - { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 32, offsetof(mavlink_high_latency_t, climb_rate) }, \ - { "gps_nsat", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency_t, gps_nsat) }, \ - { "gps_fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency_t, gps_fix_type) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency_t, battery_remaining) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency_t, temperature) }, \ - { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \ - { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \ - { "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY { \ - "HIGH_LATENCY", \ - 24, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \ - { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \ - { "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \ - { "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \ - { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \ - { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \ - { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \ - { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \ - { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 32, offsetof(mavlink_high_latency_t, climb_rate) }, \ - { "gps_nsat", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency_t, gps_nsat) }, \ - { "gps_fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency_t, gps_fix_type) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency_t, battery_remaining) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency_t, temperature) }, \ - { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \ - { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \ - { "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \ - } \ -} -#endif - -/** - * @brief Pack a high_latency 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 base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll roll (centidegrees) - * @param pitch pitch (centidegrees) - * @param heading heading (centidegrees) - * @param throttle throttle (percentage) - * @param heading_sp heading setpoint (centidegrees) - * @param latitude Latitude, expressed as degrees * 1E7 - * @param longitude Longitude, expressed as degrees * 1E7 - * @param altitude_amsl Altitude above mean sea level (meters) - * @param altitude_sp Altitude setpoint relative to the home position (meters) - * @param airspeed airspeed (m/s) - * @param airspeed_sp airspeed setpoint (m/s) - * @param groundspeed groundspeed (m/s) - * @param climb_rate climb rate (m/s) - * @param gps_nsat Number of satellites visible. If unknown, set to 255 - * @param gps_fix_type See the GPS_FIX_TYPE enum. - * @param battery_remaining Remaining battery (percentage) - * @param temperature Autopilot temperature (degrees C) - * @param temperature_air Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance distance to target (meters) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_high_latency_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#else - mavlink_high_latency_t packet; - packet.custom_mode = custom_mode; - packet.latitude = latitude; - packet.longitude = longitude; - packet.roll = roll; - packet.pitch = pitch; - packet.heading = heading; - packet.heading_sp = heading_sp; - packet.altitude_amsl = altitude_amsl; - packet.altitude_sp = altitude_sp; - packet.wp_distance = wp_distance; - packet.base_mode = base_mode; - packet.landed_state = landed_state; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.climb_rate = climb_rate; - packet.gps_nsat = gps_nsat; - packet.gps_fix_type = gps_fix_type; - packet.battery_remaining = battery_remaining; - packet.temperature = temperature; - packet.temperature_air = temperature_air; - packet.failsafe = failsafe; - packet.wp_num = wp_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -} - -/** - * @brief Pack a high_latency message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll roll (centidegrees) - * @param pitch pitch (centidegrees) - * @param heading heading (centidegrees) - * @param throttle throttle (percentage) - * @param heading_sp heading setpoint (centidegrees) - * @param latitude Latitude, expressed as degrees * 1E7 - * @param longitude Longitude, expressed as degrees * 1E7 - * @param altitude_amsl Altitude above mean sea level (meters) - * @param altitude_sp Altitude setpoint relative to the home position (meters) - * @param airspeed airspeed (m/s) - * @param airspeed_sp airspeed setpoint (m/s) - * @param groundspeed groundspeed (m/s) - * @param climb_rate climb rate (m/s) - * @param gps_nsat Number of satellites visible. If unknown, set to 255 - * @param gps_fix_type See the GPS_FIX_TYPE enum. - * @param battery_remaining Remaining battery (percentage) - * @param temperature Autopilot temperature (degrees C) - * @param temperature_air Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance distance to target (meters) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_high_latency_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t base_mode,uint32_t custom_mode,uint8_t landed_state,int16_t roll,int16_t pitch,uint16_t heading,int8_t throttle,int16_t heading_sp,int32_t latitude,int32_t longitude,int16_t altitude_amsl,int16_t altitude_sp,uint8_t airspeed,uint8_t airspeed_sp,uint8_t groundspeed,int8_t climb_rate,uint8_t gps_nsat,uint8_t gps_fix_type,uint8_t battery_remaining,int8_t temperature,int8_t temperature_air,uint8_t failsafe,uint8_t wp_num,uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#else - mavlink_high_latency_t packet; - packet.custom_mode = custom_mode; - packet.latitude = latitude; - packet.longitude = longitude; - packet.roll = roll; - packet.pitch = pitch; - packet.heading = heading; - packet.heading_sp = heading_sp; - packet.altitude_amsl = altitude_amsl; - packet.altitude_sp = altitude_sp; - packet.wp_distance = wp_distance; - packet.base_mode = base_mode; - packet.landed_state = landed_state; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.climb_rate = climb_rate; - packet.gps_nsat = gps_nsat; - packet.gps_fix_type = gps_fix_type; - packet.battery_remaining = battery_remaining; - packet.temperature = temperature; - packet.temperature_air = temperature_air; - packet.failsafe = failsafe; - packet.wp_num = wp_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -} - -/** - * @brief Encode a high_latency struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param high_latency C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_high_latency_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_high_latency_t* high_latency) -{ - return mavlink_msg_high_latency_pack(system_id, component_id, msg, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance); -} - -/** - * @brief Encode a high_latency struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param high_latency C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_high_latency_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_high_latency_t* high_latency) -{ - return mavlink_msg_high_latency_pack_chan(system_id, component_id, chan, msg, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance); -} - -/** - * @brief Send a high_latency message - * @param chan MAVLink channel to send the message - * - * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll roll (centidegrees) - * @param pitch pitch (centidegrees) - * @param heading heading (centidegrees) - * @param throttle throttle (percentage) - * @param heading_sp heading setpoint (centidegrees) - * @param latitude Latitude, expressed as degrees * 1E7 - * @param longitude Longitude, expressed as degrees * 1E7 - * @param altitude_amsl Altitude above mean sea level (meters) - * @param altitude_sp Altitude setpoint relative to the home position (meters) - * @param airspeed airspeed (m/s) - * @param airspeed_sp airspeed setpoint (m/s) - * @param groundspeed groundspeed (m/s) - * @param climb_rate climb rate (m/s) - * @param gps_nsat Number of satellites visible. If unknown, set to 255 - * @param gps_fix_type See the GPS_FIX_TYPE enum. - * @param battery_remaining Remaining battery (percentage) - * @param temperature Autopilot temperature (degrees C) - * @param temperature_air Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance distance to target (meters) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_high_latency_send(mavlink_channel_t chan, uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, buf, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#else - mavlink_high_latency_t packet; - packet.custom_mode = custom_mode; - packet.latitude = latitude; - packet.longitude = longitude; - packet.roll = roll; - packet.pitch = pitch; - packet.heading = heading; - packet.heading_sp = heading_sp; - packet.altitude_amsl = altitude_amsl; - packet.altitude_sp = altitude_sp; - packet.wp_distance = wp_distance; - packet.base_mode = base_mode; - packet.landed_state = landed_state; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.climb_rate = climb_rate; - packet.gps_nsat = gps_nsat; - packet.gps_fix_type = gps_fix_type; - packet.battery_remaining = battery_remaining; - packet.temperature = temperature; - packet.temperature_air = temperature_air; - packet.failsafe = failsafe; - packet.wp_num = wp_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)&packet, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#endif -} - -/** - * @brief Send a high_latency message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_high_latency_send_struct(mavlink_channel_t chan, const mavlink_high_latency_t* high_latency) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_high_latency_send(chan, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)high_latency, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIGH_LATENCY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_high_latency_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, buf, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#else - mavlink_high_latency_t *packet = (mavlink_high_latency_t *)msgbuf; - packet->custom_mode = custom_mode; - packet->latitude = latitude; - packet->longitude = longitude; - packet->roll = roll; - packet->pitch = pitch; - packet->heading = heading; - packet->heading_sp = heading_sp; - packet->altitude_amsl = altitude_amsl; - packet->altitude_sp = altitude_sp; - packet->wp_distance = wp_distance; - packet->base_mode = base_mode; - packet->landed_state = landed_state; - packet->throttle = throttle; - packet->airspeed = airspeed; - packet->airspeed_sp = airspeed_sp; - packet->groundspeed = groundspeed; - packet->climb_rate = climb_rate; - packet->gps_nsat = gps_nsat; - packet->gps_fix_type = gps_fix_type; - packet->battery_remaining = battery_remaining; - packet->temperature = temperature; - packet->temperature_air = temperature_air; - packet->failsafe = failsafe; - packet->wp_num = wp_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)packet, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIGH_LATENCY UNPACKING - - -/** - * @brief Get field base_mode from high_latency message - * - * @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - */ -static inline uint8_t mavlink_msg_high_latency_get_base_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field custom_mode from high_latency message - * - * @return A bitfield for use for autopilot-specific flags. - */ -static inline uint32_t mavlink_msg_high_latency_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field landed_state from high_latency message - * - * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - */ -static inline uint8_t mavlink_msg_high_latency_get_landed_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 27); -} - -/** - * @brief Get field roll from high_latency message - * - * @return roll (centidegrees) - */ -static inline int16_t mavlink_msg_high_latency_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field pitch from high_latency message - * - * @return pitch (centidegrees) - */ -static inline int16_t mavlink_msg_high_latency_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field heading from high_latency message - * - * @return heading (centidegrees) - */ -static inline uint16_t mavlink_msg_high_latency_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field throttle from high_latency message - * - * @return throttle (percentage) - */ -static inline int8_t mavlink_msg_high_latency_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 28); -} - -/** - * @brief Get field heading_sp from high_latency message - * - * @return heading setpoint (centidegrees) - */ -static inline int16_t mavlink_msg_high_latency_get_heading_sp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field latitude from high_latency message - * - * @return Latitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_high_latency_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field longitude from high_latency message - * - * @return Longitude, expressed as degrees * 1E7 - */ -static inline int32_t mavlink_msg_high_latency_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field altitude_amsl from high_latency message - * - * @return Altitude above mean sea level (meters) - */ -static inline int16_t mavlink_msg_high_latency_get_altitude_amsl(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field altitude_sp from high_latency message - * - * @return Altitude setpoint relative to the home position (meters) - */ -static inline int16_t mavlink_msg_high_latency_get_altitude_sp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field airspeed from high_latency message - * - * @return airspeed (m/s) - */ -static inline uint8_t mavlink_msg_high_latency_get_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field airspeed_sp from high_latency message - * - * @return airspeed setpoint (m/s) - */ -static inline uint8_t mavlink_msg_high_latency_get_airspeed_sp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field groundspeed from high_latency message - * - * @return groundspeed (m/s) - */ -static inline uint8_t mavlink_msg_high_latency_get_groundspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field climb_rate from high_latency message - * - * @return climb rate (m/s) - */ -static inline int8_t mavlink_msg_high_latency_get_climb_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 32); -} - -/** - * @brief Get field gps_nsat from high_latency message - * - * @return Number of satellites visible. If unknown, set to 255 - */ -static inline uint8_t mavlink_msg_high_latency_get_gps_nsat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field gps_fix_type from high_latency message - * - * @return See the GPS_FIX_TYPE enum. - */ -static inline uint8_t mavlink_msg_high_latency_get_gps_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field battery_remaining from high_latency message - * - * @return Remaining battery (percentage) - */ -static inline uint8_t mavlink_msg_high_latency_get_battery_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field temperature from high_latency message - * - * @return Autopilot temperature (degrees C) - */ -static inline int8_t mavlink_msg_high_latency_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 36); -} - -/** - * @brief Get field temperature_air from high_latency message - * - * @return Air temperature (degrees C) from airspeed sensor - */ -static inline int8_t mavlink_msg_high_latency_get_temperature_air(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 37); -} - -/** - * @brief Get field failsafe from high_latency message - * - * @return failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - */ -static inline uint8_t mavlink_msg_high_latency_get_failsafe(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 38); -} - -/** - * @brief Get field wp_num from high_latency message - * - * @return current waypoint number - */ -static inline uint8_t mavlink_msg_high_latency_get_wp_num(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 39); -} - -/** - * @brief Get field wp_distance from high_latency message - * - * @return distance to target (meters) - */ -static inline uint16_t mavlink_msg_high_latency_get_wp_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Decode a high_latency message into a struct - * - * @param msg The message to decode - * @param high_latency C-struct to decode the message contents into - */ -static inline void mavlink_msg_high_latency_decode(const mavlink_message_t* msg, mavlink_high_latency_t* high_latency) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - high_latency->custom_mode = mavlink_msg_high_latency_get_custom_mode(msg); - high_latency->latitude = mavlink_msg_high_latency_get_latitude(msg); - high_latency->longitude = mavlink_msg_high_latency_get_longitude(msg); - high_latency->roll = mavlink_msg_high_latency_get_roll(msg); - high_latency->pitch = mavlink_msg_high_latency_get_pitch(msg); - high_latency->heading = mavlink_msg_high_latency_get_heading(msg); - high_latency->heading_sp = mavlink_msg_high_latency_get_heading_sp(msg); - high_latency->altitude_amsl = mavlink_msg_high_latency_get_altitude_amsl(msg); - high_latency->altitude_sp = mavlink_msg_high_latency_get_altitude_sp(msg); - high_latency->wp_distance = mavlink_msg_high_latency_get_wp_distance(msg); - high_latency->base_mode = mavlink_msg_high_latency_get_base_mode(msg); - high_latency->landed_state = mavlink_msg_high_latency_get_landed_state(msg); - high_latency->throttle = mavlink_msg_high_latency_get_throttle(msg); - high_latency->airspeed = mavlink_msg_high_latency_get_airspeed(msg); - high_latency->airspeed_sp = mavlink_msg_high_latency_get_airspeed_sp(msg); - high_latency->groundspeed = mavlink_msg_high_latency_get_groundspeed(msg); - high_latency->climb_rate = mavlink_msg_high_latency_get_climb_rate(msg); - high_latency->gps_nsat = mavlink_msg_high_latency_get_gps_nsat(msg); - high_latency->gps_fix_type = mavlink_msg_high_latency_get_gps_fix_type(msg); - high_latency->battery_remaining = mavlink_msg_high_latency_get_battery_remaining(msg); - high_latency->temperature = mavlink_msg_high_latency_get_temperature(msg); - high_latency->temperature_air = mavlink_msg_high_latency_get_temperature_air(msg); - high_latency->failsafe = mavlink_msg_high_latency_get_failsafe(msg); - high_latency->wp_num = mavlink_msg_high_latency_get_wp_num(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIGH_LATENCY_LEN? msg->len : MAVLINK_MSG_ID_HIGH_LATENCY_LEN; - memset(high_latency, 0, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); - memcpy(high_latency, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_highres_imu.h b/include/mavlink/v2.0/common/mavlink_msg_highres_imu.h deleted file mode 100644 index be7e5d3..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_highres_imu.h +++ /dev/null @@ -1,563 +0,0 @@ -#pragma once -// MESSAGE HIGHRES_IMU PACKING - -#define MAVLINK_MSG_ID_HIGHRES_IMU 105 - -MAVPACKED( -typedef struct __mavlink_highres_imu_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float xacc; /*< X acceleration (m/s^2)*/ - float yacc; /*< Y acceleration (m/s^2)*/ - float zacc; /*< Z acceleration (m/s^2)*/ - float xgyro; /*< Angular speed around X axis (rad / sec)*/ - float ygyro; /*< Angular speed around Y axis (rad / sec)*/ - float zgyro; /*< Angular speed around Z axis (rad / sec)*/ - float xmag; /*< X Magnetic field (Gauss)*/ - float ymag; /*< Y Magnetic field (Gauss)*/ - float zmag; /*< Z Magnetic field (Gauss)*/ - float abs_pressure; /*< Absolute pressure in millibar*/ - float diff_pressure; /*< Differential pressure in millibar*/ - float pressure_alt; /*< Altitude calculated from pressure*/ - float temperature; /*< Temperature in degrees celsius*/ - uint16_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature*/ -}) mavlink_highres_imu_t; - -#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62 -#define MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN 62 -#define MAVLINK_MSG_ID_105_LEN 62 -#define MAVLINK_MSG_ID_105_MIN_LEN 62 - -#define MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93 -#define MAVLINK_MSG_ID_105_CRC 93 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \ - 105, \ - "HIGHRES_IMU", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \ - "HIGHRES_IMU", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \ - } \ -} -#endif - -/** - * @brief Pack a highres_imu 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 xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - 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.temperature = temperature; - packet.fields_updated = fields_updated; - - 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, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -} - -/** - * @brief Pack a highres_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - 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.temperature = temperature; - packet.fields_updated = fields_updated; - - 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, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -} - -/** - * @brief Encode a highres_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param highres_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) -{ - return mavlink_msg_highres_imu_pack(system_id, component_id, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); -} - -/** - * @brief Encode a highres_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param highres_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) -{ - return mavlink_msg_highres_imu_pack_chan(system_id, component_id, chan, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); -} - -/** - * @brief Send a highres_imu message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _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, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - 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.temperature = temperature; - packet.fields_updated = fields_updated; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#endif -} - -/** - * @brief Send a highres_imu message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_highres_imu_send_struct(mavlink_channel_t chan, const mavlink_highres_imu_t* highres_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_highres_imu_send(chan, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)highres_imu, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIGHRES_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _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, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - mavlink_highres_imu_t *packet = (mavlink_highres_imu_t *)msgbuf; - packet->time_usec = time_usec; - 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->temperature = temperature; - packet->fields_updated = fields_updated; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIGHRES_IMU UNPACKING - - -/** - * @brief Get field time_usec from highres_imu message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field xacc from highres_imu message - * - * @return X acceleration (m/s^2) - */ -static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yacc from highres_imu message - * - * @return Y acceleration (m/s^2) - */ -static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field zacc from highres_imu message - * - * @return Z acceleration (m/s^2) - */ -static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field xgyro from highres_imu message - * - * @return Angular speed around X axis (rad / sec) - */ -static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field ygyro from highres_imu message - * - * @return Angular speed around Y axis (rad / sec) - */ -static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field zgyro from highres_imu message - * - * @return Angular speed around Z axis (rad / sec) - */ -static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field xmag from highres_imu message - * - * @return X Magnetic field (Gauss) - */ -static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ymag from highres_imu message - * - * @return Y Magnetic field (Gauss) - */ -static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field zmag from highres_imu message - * - * @return Z Magnetic field (Gauss) - */ -static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field abs_pressure from highres_imu message - * - * @return Absolute pressure in millibar - */ -static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field diff_pressure from highres_imu message - * - * @return Differential pressure in millibar - */ -static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field pressure_alt from highres_imu message - * - * @return Altitude calculated from pressure - */ -static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field temperature from highres_imu message - * - * @return Temperature in degrees celsius - */ -static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field fields_updated from highres_imu message - * - * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - */ -static inline uint16_t mavlink_msg_highres_imu_get_fields_updated(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 60); -} - -/** - * @brief Decode a highres_imu message into a struct - * - * @param msg The message to decode - * @param highres_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_highres_imu_decode(const mavlink_message_t* msg, mavlink_highres_imu_t* highres_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - highres_imu->time_usec = mavlink_msg_highres_imu_get_time_usec(msg); - highres_imu->xacc = mavlink_msg_highres_imu_get_xacc(msg); - highres_imu->yacc = mavlink_msg_highres_imu_get_yacc(msg); - highres_imu->zacc = mavlink_msg_highres_imu_get_zacc(msg); - highres_imu->xgyro = mavlink_msg_highres_imu_get_xgyro(msg); - highres_imu->ygyro = mavlink_msg_highres_imu_get_ygyro(msg); - highres_imu->zgyro = mavlink_msg_highres_imu_get_zgyro(msg); - highres_imu->xmag = mavlink_msg_highres_imu_get_xmag(msg); - highres_imu->ymag = mavlink_msg_highres_imu_get_ymag(msg); - highres_imu->zmag = mavlink_msg_highres_imu_get_zmag(msg); - highres_imu->abs_pressure = mavlink_msg_highres_imu_get_abs_pressure(msg); - highres_imu->diff_pressure = mavlink_msg_highres_imu_get_diff_pressure(msg); - highres_imu->pressure_alt = mavlink_msg_highres_imu_get_pressure_alt(msg); - highres_imu->temperature = mavlink_msg_highres_imu_get_temperature(msg); - highres_imu->fields_updated = mavlink_msg_highres_imu_get_fields_updated(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIGHRES_IMU_LEN? msg->len : MAVLINK_MSG_ID_HIGHRES_IMU_LEN; - memset(highres_imu, 0, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); - memcpy(highres_imu, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_hil_actuator_controls.h b/include/mavlink/v2.0/common/mavlink_msg_hil_actuator_controls.h deleted file mode 100644 index f60e920..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_hil_actuator_controls.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE HIL_ACTUATOR_CONTROLS PACKING - -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS 93 - -MAVPACKED( -typedef struct __mavlink_hil_actuator_controls_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - uint64_t flags; /*< Flags as bitfield, reserved for future use.*/ - float controls[16]; /*< Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.*/ - uint8_t mode; /*< System mode (MAV_MODE), includes arming state.*/ -}) mavlink_hil_actuator_controls_t; - -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN 81 -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN 81 -#define MAVLINK_MSG_ID_93_LEN 81 -#define MAVLINK_MSG_ID_93_MIN_LEN 81 - -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC 47 -#define MAVLINK_MSG_ID_93_CRC 47 - -#define MAVLINK_MSG_HIL_ACTUATOR_CONTROLS_FIELD_CONTROLS_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS { \ - 93, \ - "HIL_ACTUATOR_CONTROLS", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS { \ - "HIL_ACTUATOR_CONTROLS", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_actuator_controls 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 since UNIX epoch or microseconds since system boot) - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode (MAV_MODE), includes arming state. - * @param flags Flags as bitfield, reserved for future use. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#else - mavlink_hil_actuator_controls_t packet; - packet.time_usec = time_usec; - packet.flags = flags; - packet.mode = mode; - mav_array_memcpy(packet.controls, controls, sizeof(float)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -} - -/** - * @brief Pack a hil_actuator_controls message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode (MAV_MODE), includes arming state. - * @param flags Flags as bitfield, reserved for future use. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *controls,uint8_t mode,uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#else - mavlink_hil_actuator_controls_t packet; - packet.time_usec = time_usec; - packet.flags = flags; - packet.mode = mode; - mav_array_memcpy(packet.controls, controls, sizeof(float)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -} - -/** - * @brief Encode a hil_actuator_controls struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_actuator_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ - return mavlink_msg_hil_actuator_controls_pack(system_id, component_id, msg, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags); -} - -/** - * @brief Encode a hil_actuator_controls struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_actuator_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ - return mavlink_msg_hil_actuator_controls_pack_chan(system_id, component_id, chan, msg, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags); -} - -/** - * @brief Send a hil_actuator_controls message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode (MAV_MODE), includes arming state. - * @param flags Flags as bitfield, reserved for future use. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_actuator_controls_send(mavlink_channel_t chan, uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#else - mavlink_hil_actuator_controls_t packet; - packet.time_usec = time_usec; - packet.flags = flags; - packet.mode = mode; - mav_array_memcpy(packet.controls, controls, sizeof(float)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#endif -} - -/** - * @brief Send a hil_actuator_controls message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_actuator_controls_send_struct(mavlink_channel_t chan, const mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_actuator_controls_send(chan, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)hil_actuator_controls, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_actuator_controls_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#else - mavlink_hil_actuator_controls_t *packet = (mavlink_hil_actuator_controls_t *)msgbuf; - packet->time_usec = time_usec; - packet->flags = flags; - packet->mode = mode; - mav_array_memcpy(packet->controls, controls, sizeof(float)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_ACTUATOR_CONTROLS UNPACKING - - -/** - * @brief Get field time_usec from hil_actuator_controls message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_actuator_controls_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field controls from hil_actuator_controls message - * - * @return Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_get_controls(const mavlink_message_t* msg, float *controls) -{ - return _MAV_RETURN_float_array(msg, controls, 16, 16); -} - -/** - * @brief Get field mode from hil_actuator_controls message - * - * @return System mode (MAV_MODE), includes arming state. - */ -static inline uint8_t mavlink_msg_hil_actuator_controls_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 80); -} - -/** - * @brief Get field flags from hil_actuator_controls message - * - * @return Flags as bitfield, reserved for future use. - */ -static inline uint64_t mavlink_msg_hil_actuator_controls_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Decode a hil_actuator_controls message into a struct - * - * @param msg The message to decode - * @param hil_actuator_controls C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_actuator_controls_decode(const mavlink_message_t* msg, mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_actuator_controls->time_usec = mavlink_msg_hil_actuator_controls_get_time_usec(msg); - hil_actuator_controls->flags = mavlink_msg_hil_actuator_controls_get_flags(msg); - mavlink_msg_hil_actuator_controls_get_controls(msg, hil_actuator_controls->controls); - hil_actuator_controls->mode = mavlink_msg_hil_actuator_controls_get_mode(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN? msg->len : MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN; - memset(hil_actuator_controls, 0, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); - memcpy(hil_actuator_controls, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_hil_controls.h b/include/mavlink/v2.0/common/mavlink_msg_hil_controls.h deleted file mode 100644 index 39dca7e..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_hil_controls.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE HIL_CONTROLS PACKING - -#define MAVLINK_MSG_ID_HIL_CONTROLS 91 - -MAVPACKED( -typedef struct __mavlink_hil_controls_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - float roll_ailerons; /*< Control output -1 .. 1*/ - float pitch_elevator; /*< Control output -1 .. 1*/ - float yaw_rudder; /*< Control output -1 .. 1*/ - float throttle; /*< Throttle 0 .. 1*/ - float aux1; /*< Aux 1, -1 .. 1*/ - float aux2; /*< Aux 2, -1 .. 1*/ - float aux3; /*< Aux 3, -1 .. 1*/ - float aux4; /*< Aux 4, -1 .. 1*/ - uint8_t mode; /*< System mode (MAV_MODE)*/ - uint8_t nav_mode; /*< Navigation mode (MAV_NAV_MODE)*/ -}) mavlink_hil_controls_t; - -#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 -#define MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN 42 -#define MAVLINK_MSG_ID_91_LEN 42 -#define MAVLINK_MSG_ID_91_MIN_LEN 42 - -#define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63 -#define MAVLINK_MSG_ID_91_CRC 63 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ - 91, \ - "HIL_CONTROLS", \ - 11, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \ - { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ - { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ - { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ - { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ - { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \ - { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \ - { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \ - { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \ - { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ - "HIL_CONTROLS", \ - 11, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \ - { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ - { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ - { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ - { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ - { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \ - { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \ - { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \ - { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \ - { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_controls 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 since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - - 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, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -} - -/** - * @brief Pack a hil_controls message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - - 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, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -} - -/** - * @brief Encode a hil_controls struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) -{ - return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); -} - -/** - * @brief Encode a hil_controls struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) -{ - return mavlink_msg_hil_controls_pack_chan(system_id, component_id, chan, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); -} - -/** - * @brief Send a hil_controls message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _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, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#endif -} - -/** - * @brief Send a hil_controls message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_controls_send_struct(mavlink_channel_t chan, const mavlink_hil_controls_t* hil_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_controls_send(chan, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)hil_controls, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll_ailerons); - _mav_put_float(buf, 12, pitch_elevator); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _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, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - mavlink_hil_controls_t *packet = (mavlink_hil_controls_t *)msgbuf; - packet->time_usec = time_usec; - packet->roll_ailerons = roll_ailerons; - packet->pitch_elevator = pitch_elevator; - packet->yaw_rudder = yaw_rudder; - packet->throttle = throttle; - packet->aux1 = aux1; - packet->aux2 = aux2; - packet->aux3 = aux3; - packet->aux4 = aux4; - packet->mode = mode; - packet->nav_mode = nav_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_CONTROLS UNPACKING - - -/** - * @brief Get field time_usec from hil_controls message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field roll_ailerons from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pitch_elevator from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw_rudder from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field throttle from hil_controls message - * - * @return Throttle 0 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field aux1 from hil_controls message - * - * @return Aux 1, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field aux2 from hil_controls message - * - * @return Aux 2, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field aux3 from hil_controls message - * - * @return Aux 3, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field aux4 from hil_controls message - * - * @return Aux 4, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field mode from hil_controls message - * - * @return System mode (MAV_MODE) - */ -static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field nav_mode from hil_controls message - * - * @return Navigation mode (MAV_NAV_MODE) - */ -static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Decode a hil_controls message into a struct - * - * @param msg The message to decode - * @param hil_controls C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_controls->time_usec = mavlink_msg_hil_controls_get_time_usec(msg); - hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg); - hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg); - hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg); - hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg); - hil_controls->aux1 = mavlink_msg_hil_controls_get_aux1(msg); - hil_controls->aux2 = mavlink_msg_hil_controls_get_aux2(msg); - hil_controls->aux3 = mavlink_msg_hil_controls_get_aux3(msg); - hil_controls->aux4 = mavlink_msg_hil_controls_get_aux4(msg); - hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg); - hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_CONTROLS_LEN? msg->len : MAVLINK_MSG_ID_HIL_CONTROLS_LEN; - memset(hil_controls, 0, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); - memcpy(hil_controls, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_hil_gps.h b/include/mavlink/v2.0/common/mavlink_msg_hil_gps.h deleted file mode 100644 index 393006f..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_hil_gps.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE HIL_GPS PACKING - -#define MAVLINK_MSG_ID_HIL_GPS 113 - -MAVPACKED( -typedef struct __mavlink_hil_gps_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ - int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535*/ - uint16_t vel; /*< GPS ground speed in cm/s. If unknown, set to: 65535*/ - int16_t vn; /*< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame*/ - int16_t ve; /*< GPS velocity in cm/s in EAST direction in earth-fixed NED frame*/ - int16_t vd; /*< GPS velocity in cm/s in DOWN direction in earth-fixed NED frame*/ - uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535*/ - uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ -}) mavlink_hil_gps_t; - -#define MAVLINK_MSG_ID_HIL_GPS_LEN 36 -#define MAVLINK_MSG_ID_HIL_GPS_MIN_LEN 36 -#define MAVLINK_MSG_ID_113_LEN 36 -#define MAVLINK_MSG_ID_113_MIN_LEN 36 - -#define MAVLINK_MSG_ID_HIL_GPS_CRC 124 -#define MAVLINK_MSG_ID_113_CRC 124 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_GPS { \ - 113, \ - "HIL_GPS", \ - 13, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \ - { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_GPS { \ - "HIL_GPS", \ - 13, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \ - { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_gps 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 since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed in cm/s. If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_GPS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -} - -/** - * @brief Pack a hil_gps message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed in cm/s. If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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,int16_t vn,int16_t ve,int16_t vd,uint16_t cog,uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_GPS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -} - -/** - * @brief Encode a hil_gps struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_gps C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) -{ - return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); -} - -/** - * @brief Encode a hil_gps struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_gps C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) -{ - return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); -} - -/** - * @brief Send a hil_gps message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed in cm/s. If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#endif -} - -/** - * @brief Send a hil_gps message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_gps_send_struct(mavlink_channel_t chan, const mavlink_hil_gps_t* hil_gps) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_gps_send(chan, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)hil_gps, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, 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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->vn = vn; - packet->ve = ve; - packet->vd = vd; - packet->cog = cog; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_GPS UNPACKING - - -/** - * @brief Get field time_usec from hil_gps message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from hil_gps message - * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - */ -static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field lat from hil_gps message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from hil_gps message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from hil_gps message - * - * @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from hil_gps message - * - * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field epv from hil_gps message - * - * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field vel from hil_gps message - * - * @return GPS ground speed in cm/s. If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field vn from hil_gps message - * - * @return GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 26); -} - -/** - * @brief Get field ve from hil_gps message - * - * @return GPS velocity in cm/s in EAST direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 28); -} - -/** - * @brief Get field vd from hil_gps message - * - * @return GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 30); -} - -/** - * @brief Get field cog from hil_gps message - * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field satellites_visible from hil_gps message - * - * @return Number of satellites visible. If unknown, set to 255 - */ -static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Decode a hil_gps message into a struct - * - * @param msg The message to decode - * @param hil_gps C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavlink_hil_gps_t* hil_gps) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_gps->time_usec = mavlink_msg_hil_gps_get_time_usec(msg); - hil_gps->lat = mavlink_msg_hil_gps_get_lat(msg); - hil_gps->lon = mavlink_msg_hil_gps_get_lon(msg); - hil_gps->alt = mavlink_msg_hil_gps_get_alt(msg); - hil_gps->eph = mavlink_msg_hil_gps_get_eph(msg); - hil_gps->epv = mavlink_msg_hil_gps_get_epv(msg); - hil_gps->vel = mavlink_msg_hil_gps_get_vel(msg); - hil_gps->vn = mavlink_msg_hil_gps_get_vn(msg); - hil_gps->ve = mavlink_msg_hil_gps_get_ve(msg); - hil_gps->vd = mavlink_msg_hil_gps_get_vd(msg); - hil_gps->cog = mavlink_msg_hil_gps_get_cog(msg); - hil_gps->fix_type = mavlink_msg_hil_gps_get_fix_type(msg); - hil_gps->satellites_visible = mavlink_msg_hil_gps_get_satellites_visible(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_GPS_LEN? msg->len : MAVLINK_MSG_ID_HIL_GPS_LEN; - memset(hil_gps, 0, MAVLINK_MSG_ID_HIL_GPS_LEN); - memcpy(hil_gps, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_hil_optical_flow.h b/include/mavlink/v2.0/common/mavlink_msg_hil_optical_flow.h deleted file mode 100644 index 9d1cf8e..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_hil_optical_flow.h +++ /dev/null @@ -1,488 +0,0 @@ -#pragma once -// MESSAGE HIL_OPTICAL_FLOW PACKING - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114 - -MAVPACKED( -typedef struct __mavlink_hil_optical_flow_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ - float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ - float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ - float integrated_xgyro; /*< RH rotation around X axis (rad)*/ - float integrated_ygyro; /*< RH rotation around Y axis (rad)*/ - float integrated_zgyro; /*< RH rotation around Z axis (rad)*/ - uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/ - float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/ - int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ -}) mavlink_hil_optical_flow_t; - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44 -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN 44 -#define MAVLINK_MSG_ID_114_LEN 44 -#define MAVLINK_MSG_ID_114_MIN_LEN 44 - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 237 -#define MAVLINK_MSG_ID_114_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \ - 114, \ - "HIL_OPTICAL_FLOW", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \ - "HIL_OPTICAL_FLOW", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_optical_flow 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 sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -} - -/** - * @brief Pack a hil_optical_flow message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_id,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -} - -/** - * @brief Encode a hil_optical_flow struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) -{ - return mavlink_msg_hil_optical_flow_pack(system_id, component_id, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); -} - -/** - * @brief Encode a hil_optical_flow struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) -{ - return mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, chan, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); -} - -/** - * @brief Send a hil_optical_flow message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#endif -} - -/** - * @brief Send a hil_optical_flow message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_optical_flow_send_struct(mavlink_channel_t chan, const mavlink_hil_optical_flow_t* hil_optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_optical_flow_send(chan, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)hil_optical_flow, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - mavlink_hil_optical_flow_t *packet = (mavlink_hil_optical_flow_t *)msgbuf; - packet->time_usec = time_usec; - packet->integration_time_us = integration_time_us; - packet->integrated_x = integrated_x; - packet->integrated_y = integrated_y; - packet->integrated_xgyro = integrated_xgyro; - packet->integrated_ygyro = integrated_ygyro; - packet->integrated_zgyro = integrated_zgyro; - packet->time_delta_distance_us = time_delta_distance_us; - packet->distance = distance; - packet->temperature = temperature; - packet->sensor_id = sensor_id; - packet->quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_OPTICAL_FLOW UNPACKING - - -/** - * @brief Get field time_usec from hil_optical_flow message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from hil_optical_flow message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field integration_time_us from hil_optical_flow message - * - * @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - */ -static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field integrated_x from hil_optical_flow message - * - * @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field integrated_y from hil_optical_flow message - * - * @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field integrated_xgyro from hil_optical_flow message - * - * @return RH rotation around X axis (rad) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field integrated_ygyro from hil_optical_flow message - * - * @return RH rotation around Y axis (rad) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field integrated_zgyro from hil_optical_flow message - * - * @return RH rotation around Z axis (rad) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field temperature from hil_optical_flow message - * - * @return Temperature * 100 in centi-degrees Celsius - */ -static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 40); -} - -/** - * @brief Get field quality from hil_optical_flow message - * - * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - */ -static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 43); -} - -/** - * @brief Get field time_delta_distance_us from hil_optical_flow message - * - * @return Time in microseconds since the distance was sampled. - */ -static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 32); -} - -/** - * @brief Get field distance from hil_optical_flow message - * - * @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -static inline float mavlink_msg_hil_optical_flow_get_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a hil_optical_flow message into a struct - * - * @param msg The message to decode - * @param hil_optical_flow C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_optical_flow_decode(const mavlink_message_t* msg, mavlink_hil_optical_flow_t* hil_optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_optical_flow->time_usec = mavlink_msg_hil_optical_flow_get_time_usec(msg); - hil_optical_flow->integration_time_us = mavlink_msg_hil_optical_flow_get_integration_time_us(msg); - hil_optical_flow->integrated_x = mavlink_msg_hil_optical_flow_get_integrated_x(msg); - hil_optical_flow->integrated_y = mavlink_msg_hil_optical_flow_get_integrated_y(msg); - hil_optical_flow->integrated_xgyro = mavlink_msg_hil_optical_flow_get_integrated_xgyro(msg); - hil_optical_flow->integrated_ygyro = mavlink_msg_hil_optical_flow_get_integrated_ygyro(msg); - hil_optical_flow->integrated_zgyro = mavlink_msg_hil_optical_flow_get_integrated_zgyro(msg); - hil_optical_flow->time_delta_distance_us = mavlink_msg_hil_optical_flow_get_time_delta_distance_us(msg); - hil_optical_flow->distance = mavlink_msg_hil_optical_flow_get_distance(msg); - hil_optical_flow->temperature = mavlink_msg_hil_optical_flow_get_temperature(msg); - hil_optical_flow->sensor_id = mavlink_msg_hil_optical_flow_get_sensor_id(msg); - hil_optical_flow->quality = mavlink_msg_hil_optical_flow_get_quality(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN? msg->len : MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN; - memset(hil_optical_flow, 0, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); - memcpy(hil_optical_flow, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_hil_rc_inputs_raw.h b/include/mavlink/v2.0/common/mavlink_msg_hil_rc_inputs_raw.h deleted file mode 100644 index 04b8a45..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_hil_rc_inputs_raw.h +++ /dev/null @@ -1,538 +0,0 @@ -#pragma once -// MESSAGE HIL_RC_INPUTS_RAW PACKING - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92 - -MAVPACKED( -typedef struct __mavlink_hil_rc_inputs_raw_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds*/ - uint16_t chan9_raw; /*< RC channel 9 value, in microseconds*/ - uint16_t chan10_raw; /*< RC channel 10 value, in microseconds*/ - uint16_t chan11_raw; /*< RC channel 11 value, in microseconds*/ - uint16_t chan12_raw; /*< RC channel 12 value, in microseconds*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 255: 100%*/ -}) mavlink_hil_rc_inputs_raw_t; - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN 33 -#define MAVLINK_MSG_ID_92_LEN 33 -#define MAVLINK_MSG_ID_92_MIN_LEN 33 - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC 54 -#define MAVLINK_MSG_ID_92_CRC 54 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ - 92, \ - "HIL_RC_INPUTS_RAW", \ - 14, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ - "HIL_RC_INPUTS_RAW", \ - 14, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_rc_inputs_raw 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 since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - - 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; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -} - -/** - * @brief Pack a hil_rc_inputs_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - - 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; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -} - -/** - * @brief Encode a hil_rc_inputs_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_rc_inputs_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ - return mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); -} - -/** - * @brief Encode a hil_rc_inputs_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_rc_inputs_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ - return mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, chan, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); -} - -/** - * @brief Send a hil_rc_inputs_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - mavlink_hil_rc_inputs_raw_t packet; - packet.time_usec = time_usec; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#endif -} - -/** - * @brief Send a hil_rc_inputs_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_rc_inputs_raw_send_struct(mavlink_channel_t chan, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_rc_inputs_raw_send(chan, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)hil_rc_inputs_raw, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_rc_inputs_raw_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, chan1_raw); - _mav_put_uint16_t(buf, 10, chan2_raw); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - mavlink_hil_rc_inputs_raw_t *packet = (mavlink_hil_rc_inputs_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->chan9_raw = chan9_raw; - packet->chan10_raw = chan10_raw; - packet->chan11_raw = chan11_raw; - packet->chan12_raw = chan12_raw; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_RC_INPUTS_RAW UNPACKING - - -/** - * @brief Get field time_usec from hil_rc_inputs_raw message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field chan1_raw from hil_rc_inputs_raw message - * - * @return RC channel 1 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan2_raw from hil_rc_inputs_raw message - * - * @return RC channel 2 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan3_raw from hil_rc_inputs_raw message - * - * @return RC channel 3 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan4_raw from hil_rc_inputs_raw message - * - * @return RC channel 4 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan5_raw from hil_rc_inputs_raw message - * - * @return RC channel 5 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan6_raw from hil_rc_inputs_raw message - * - * @return RC channel 6 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field chan7_raw from hil_rc_inputs_raw message - * - * @return RC channel 7 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field chan8_raw from hil_rc_inputs_raw message - * - * @return RC channel 8 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field chan9_raw from hil_rc_inputs_raw message - * - * @return RC channel 9 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field chan10_raw from hil_rc_inputs_raw message - * - * @return RC channel 10 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field chan11_raw from hil_rc_inputs_raw message - * - * @return RC channel 11 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field chan12_raw from hil_rc_inputs_raw message - * - * @return RC channel 12 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field rssi from hil_rc_inputs_raw message - * - * @return Receive signal strength indicator, 0: 0%, 255: 100% - */ -static inline uint8_t mavlink_msg_hil_rc_inputs_raw_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Decode a hil_rc_inputs_raw message into a struct - * - * @param msg The message to decode - * @param hil_rc_inputs_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_rc_inputs_raw_decode(const mavlink_message_t* msg, mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_rc_inputs_raw->time_usec = mavlink_msg_hil_rc_inputs_raw_get_time_usec(msg); - hil_rc_inputs_raw->chan1_raw = mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(msg); - hil_rc_inputs_raw->chan2_raw = mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(msg); - hil_rc_inputs_raw->chan3_raw = mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(msg); - hil_rc_inputs_raw->chan4_raw = mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(msg); - hil_rc_inputs_raw->chan5_raw = mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(msg); - hil_rc_inputs_raw->chan6_raw = mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(msg); - hil_rc_inputs_raw->chan7_raw = mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(msg); - hil_rc_inputs_raw->chan8_raw = mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(msg); - hil_rc_inputs_raw->chan9_raw = mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(msg); - hil_rc_inputs_raw->chan10_raw = mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(msg); - hil_rc_inputs_raw->chan11_raw = mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN? msg->len : MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN; - memset(hil_rc_inputs_raw, 0, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); - memcpy(hil_rc_inputs_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_hil_sensor.h b/include/mavlink/v2.0/common/mavlink_msg_hil_sensor.h deleted file mode 100644 index e7f561d..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_hil_sensor.h +++ /dev/null @@ -1,563 +0,0 @@ -#pragma once -// MESSAGE HIL_SENSOR PACKING - -#define MAVLINK_MSG_ID_HIL_SENSOR 107 - -MAVPACKED( -typedef struct __mavlink_hil_sensor_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float xacc; /*< X acceleration (m/s^2)*/ - float yacc; /*< Y acceleration (m/s^2)*/ - float zacc; /*< Z acceleration (m/s^2)*/ - float xgyro; /*< Angular speed around X axis in body frame (rad / sec)*/ - float ygyro; /*< Angular speed around Y axis in body frame (rad / sec)*/ - float zgyro; /*< Angular speed around Z axis in body frame (rad / sec)*/ - float xmag; /*< X Magnetic field (Gauss)*/ - float ymag; /*< Y Magnetic field (Gauss)*/ - float zmag; /*< Z Magnetic field (Gauss)*/ - float abs_pressure; /*< Absolute pressure in millibar*/ - float diff_pressure; /*< Differential pressure (airspeed) in millibar*/ - float pressure_alt; /*< Altitude calculated from pressure*/ - float temperature; /*< Temperature in degrees celsius*/ - uint32_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.*/ -}) mavlink_hil_sensor_t; - -#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 64 -#define MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN 64 -#define MAVLINK_MSG_ID_107_LEN 64 -#define MAVLINK_MSG_ID_107_MIN_LEN 64 - -#define MAVLINK_MSG_ID_HIL_SENSOR_CRC 108 -#define MAVLINK_MSG_ID_107_CRC 108 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \ - 107, \ - "HIL_SENSOR", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_sensor_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_sensor_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_sensor_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_sensor_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_sensor_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_sensor_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_sensor_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_sensor_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_sensor_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hil_sensor_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hil_sensor_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hil_sensor_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hil_sensor_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hil_sensor_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT32_T, 0, 60, offsetof(mavlink_hil_sensor_t, fields_updated) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \ - "HIL_SENSOR", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_sensor_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_sensor_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_sensor_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_sensor_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_sensor_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_sensor_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_sensor_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_sensor_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_sensor_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hil_sensor_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hil_sensor_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hil_sensor_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hil_sensor_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hil_sensor_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT32_T, 0, 60, offsetof(mavlink_hil_sensor_t, fields_updated) }, \ - } \ -} -#endif - -/** - * @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 xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. - * @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 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, 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, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, 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.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.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; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -} - -/** - * @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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. - * @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 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,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, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, 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.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.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; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -} - -/** - * @brief Encode a hil_sensor struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param 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->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->temperature, hil_sensor->fields_updated); -} - -/** - * @brief Encode a hil_sensor struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor) -{ - return mavlink_msg_hil_sensor_pack_chan(system_id, component_id, chan, msg, hil_sensor->time_usec, 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->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 xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_sensor_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, 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, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - mavlink_hil_sensor_t packet; - packet.time_usec = time_usec; - 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.temperature = temperature; - packet.fields_updated = fields_updated; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#endif -} - -/** - * @brief Send a hil_sensor message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_sensor_send_struct(mavlink_channel_t chan, const mavlink_hil_sensor_t* hil_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_sensor_send(chan, hil_sensor->time_usec, 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->temperature, hil_sensor->fields_updated); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)hil_sensor, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, 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, uint32_t fields_updated) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - mavlink_hil_sensor_t *packet = (mavlink_hil_sensor_t *)msgbuf; - packet->time_usec = time_usec; - 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->temperature = temperature; - packet->fields_updated = fields_updated; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#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 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, 8); -} - -/** - * @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, 12); -} - -/** - * @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, 16); -} - -/** - * @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, 20); -} - -/** - * @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, 24); -} - -/** - * @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, 28); -} - -/** - * @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, 32); -} - -/** - * @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, 36); -} - -/** - * @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, 40); -} - -/** - * @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, 44); -} - -/** - * @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, 48); -} - -/** - * @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, 52); -} - -/** - * @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, 56); -} - -/** - * @brief Get field fields_updated from hil_sensor message - * - * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. - */ -static inline uint32_t mavlink_msg_hil_sensor_get_fields_updated(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 60); -} - -/** - * @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 || !MAVLINK_ALIGNED_FIELDS - hil_sensor->time_usec = mavlink_msg_hil_sensor_get_time_usec(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->temperature = mavlink_msg_hil_sensor_get_temperature(msg); - hil_sensor->fields_updated = mavlink_msg_hil_sensor_get_fields_updated(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_HIL_SENSOR_LEN; - memset(hil_sensor, 0, MAVLINK_MSG_ID_HIL_SENSOR_LEN); - memcpy(hil_sensor, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_hil_state.h b/include/mavlink/v2.0/common/mavlink_msg_hil_state.h deleted file mode 100644 index 722c583..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_hil_state.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE HIL_STATE PACKING - -#define MAVLINK_MSG_ID_HIL_STATE 90 - -MAVPACKED( -typedef struct __mavlink_hil_state_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - float roll; /*< Roll angle (rad)*/ - float pitch; /*< Pitch angle (rad)*/ - float yaw; /*< Yaw angle (rad)*/ - float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/ - float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/ - float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/ - int32_t lat; /*< Latitude, expressed as * 1E7*/ - int32_t lon; /*< Longitude, expressed as * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/ - int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/ - int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/ - int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ -}) mavlink_hil_state_t; - -#define MAVLINK_MSG_ID_HIL_STATE_LEN 56 -#define MAVLINK_MSG_ID_HIL_STATE_MIN_LEN 56 -#define MAVLINK_MSG_ID_90_LEN 56 -#define MAVLINK_MSG_ID_90_MIN_LEN 56 - -#define MAVLINK_MSG_ID_HIL_STATE_CRC 183 -#define MAVLINK_MSG_ID_90_CRC 183 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_STATE { \ - 90, \ - "HIL_STATE", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_STATE { \ - "HIL_STATE", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_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 time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - - 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, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -} - -/** - * @brief Pack a hil_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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - - 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, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -} - -/** - * @brief Encode a hil_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) -{ - return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); -} - -/** - * @brief Encode a hil_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) -{ - return mavlink_msg_hil_state_pack_chan(system_id, component_id, chan, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); -} - -/** - * @brief Send a hil_state message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _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, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#endif -} - -/** - * @brief Send a hil_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_state_send_struct(mavlink_channel_t chan, const mavlink_hil_state_t* hil_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_state_send(chan, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)hil_state, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _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, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - mavlink_hil_state_t *packet = (mavlink_hil_state_t *)msgbuf; - packet->time_usec = time_usec; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_STATE UNPACKING - - -/** - * @brief Get field time_usec from hil_state message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field roll from hil_state message - * - * @return Roll angle (rad) - */ -static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pitch from hil_state message - * - * @return Pitch angle (rad) - */ -static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw from hil_state message - * - * @return Yaw angle (rad) - */ -static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field rollspeed from hil_state message - * - * @return Body frame roll / phi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitchspeed from hil_state message - * - * @return Body frame pitch / theta angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yawspeed from hil_state message - * - * @return Body frame yaw / psi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field lat from hil_state message - * - * @return Latitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 32); -} - -/** - * @brief Get field lon from hil_state message - * - * @return Longitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 36); -} - -/** - * @brief Get field alt from hil_state message - * - * @return Altitude in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 40); -} - -/** - * @brief Get field vx from hil_state message - * - * @return Ground X Speed (Latitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 44); -} - -/** - * @brief Get field vy from hil_state message - * - * @return Ground Y Speed (Longitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 46); -} - -/** - * @brief Get field vz from hil_state message - * - * @return Ground Z Speed (Altitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 48); -} - -/** - * @brief Get field xacc from hil_state message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 50); -} - -/** - * @brief Get field yacc from hil_state message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 52); -} - -/** - * @brief Get field zacc from hil_state message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 54); -} - -/** - * @brief Decode a hil_state message into a struct - * - * @param msg The message to decode - * @param hil_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg); - hil_state->roll = mavlink_msg_hil_state_get_roll(msg); - hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg); - hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg); - hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg); - hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg); - hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg); - hil_state->lat = mavlink_msg_hil_state_get_lat(msg); - hil_state->lon = mavlink_msg_hil_state_get_lon(msg); - hil_state->alt = mavlink_msg_hil_state_get_alt(msg); - hil_state->vx = mavlink_msg_hil_state_get_vx(msg); - hil_state->vy = mavlink_msg_hil_state_get_vy(msg); - hil_state->vz = mavlink_msg_hil_state_get_vz(msg); - hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg); - hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg); - hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_STATE_LEN? msg->len : MAVLINK_MSG_ID_HIL_STATE_LEN; - memset(hil_state, 0, MAVLINK_MSG_ID_HIL_STATE_LEN); - memcpy(hil_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_hil_state_quaternion.h b/include/mavlink/v2.0/common/mavlink_msg_hil_state_quaternion.h deleted file mode 100644 index 3ad8071..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_hil_state_quaternion.h +++ /dev/null @@ -1,580 +0,0 @@ -#pragma once -// MESSAGE HIL_STATE_QUATERNION PACKING - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115 - -MAVPACKED( -typedef struct __mavlink_hil_state_quaternion_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - float attitude_quaternion[4]; /*< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)*/ - float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/ - float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/ - float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/ - int32_t lat; /*< Latitude, expressed as * 1E7*/ - int32_t lon; /*< Longitude, expressed as * 1E7*/ - int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/ - int16_t vx; /*< Ground X Speed (Latitude), expressed as cm/s*/ - int16_t vy; /*< Ground Y Speed (Longitude), expressed as cm/s*/ - int16_t vz; /*< Ground Z Speed (Altitude), expressed as cm/s*/ - uint16_t ind_airspeed; /*< Indicated airspeed, expressed as cm/s*/ - uint16_t true_airspeed; /*< True airspeed, expressed as cm/s*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ -}) mavlink_hil_state_quaternion_t; - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64 -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN 64 -#define MAVLINK_MSG_ID_115_LEN 64 -#define MAVLINK_MSG_ID_115_MIN_LEN 64 - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4 -#define MAVLINK_MSG_ID_115_CRC 4 - -#define MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_ATTITUDE_QUATERNION_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \ - 115, \ - "HIL_STATE_QUATERNION", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \ - { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \ - { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \ - { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \ - "HIL_STATE_QUATERNION", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \ - { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \ - { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \ - { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_state_quaternion 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 since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as cm/s - * @param vy Ground Y Speed (Longitude), expressed as cm/s - * @param vz Ground Z Speed (Altitude), expressed as cm/s - * @param ind_airspeed Indicated airspeed, expressed as cm/s - * @param true_airspeed True airspeed, expressed as cm/s - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -} - -/** - * @brief Pack a hil_state_quaternion message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as cm/s - * @param vy Ground Y Speed (Longitude), expressed as cm/s - * @param vz Ground Z Speed (Altitude), expressed as cm/s - * @param ind_airspeed Indicated airspeed, expressed as cm/s - * @param true_airspeed True airspeed, expressed as cm/s - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t ind_airspeed,uint16_t true_airspeed,int16_t xacc,int16_t yacc,int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -} - -/** - * @brief Encode a hil_state_quaternion struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_state_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ - return mavlink_msg_hil_state_quaternion_pack(system_id, component_id, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); -} - -/** - * @brief Encode a hil_state_quaternion struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_state_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ - return mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, chan, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); -} - -/** - * @brief Send a hil_state_quaternion message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as cm/s - * @param vy Ground Y Speed (Longitude), expressed as cm/s - * @param vz Ground Z Speed (Altitude), expressed as cm/s - * @param ind_airspeed Indicated airspeed, expressed as cm/s - * @param true_airspeed True airspeed, expressed as cm/s - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_state_quaternion_send(mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#endif -} - -/** - * @brief Send a hil_state_quaternion message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_state_quaternion_send_struct(mavlink_channel_t chan, const mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_state_quaternion_send(chan, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)hil_state_quaternion, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - mavlink_hil_state_quaternion_t *packet = (mavlink_hil_state_quaternion_t *)msgbuf; - packet->time_usec = time_usec; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->ind_airspeed = ind_airspeed; - packet->true_airspeed = true_airspeed; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - mav_array_memcpy(packet->attitude_quaternion, attitude_quaternion, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_STATE_QUATERNION UNPACKING - - -/** - * @brief Get field time_usec from hil_state_quaternion message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field attitude_quaternion from hil_state_quaternion message - * - * @return Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(const mavlink_message_t* msg, float *attitude_quaternion) -{ - return _MAV_RETURN_float_array(msg, attitude_quaternion, 4, 8); -} - -/** - * @brief Get field rollspeed from hil_state_quaternion message - * - * @return Body frame roll / phi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field pitchspeed from hil_state_quaternion message - * - * @return Body frame pitch / theta angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field yawspeed from hil_state_quaternion message - * - * @return Body frame yaw / psi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field lat from hil_state_quaternion message - * - * @return Latitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 36); -} - -/** - * @brief Get field lon from hil_state_quaternion message - * - * @return Longitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 40); -} - -/** - * @brief Get field alt from hil_state_quaternion message - * - * @return Altitude in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 44); -} - -/** - * @brief Get field vx from hil_state_quaternion message - * - * @return Ground X Speed (Latitude), expressed as cm/s - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 48); -} - -/** - * @brief Get field vy from hil_state_quaternion message - * - * @return Ground Y Speed (Longitude), expressed as cm/s - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 50); -} - -/** - * @brief Get field vz from hil_state_quaternion message - * - * @return Ground Z Speed (Altitude), expressed as cm/s - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 52); -} - -/** - * @brief Get field ind_airspeed from hil_state_quaternion message - * - * @return Indicated airspeed, expressed as cm/s - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 54); -} - -/** - * @brief Get field true_airspeed from hil_state_quaternion message - * - * @return True airspeed, expressed as cm/s - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 56); -} - -/** - * @brief Get field xacc from hil_state_quaternion message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 58); -} - -/** - * @brief Get field yacc from hil_state_quaternion message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 60); -} - -/** - * @brief Get field zacc from hil_state_quaternion message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 62); -} - -/** - * @brief Decode a hil_state_quaternion message into a struct - * - * @param msg The message to decode - * @param hil_state_quaternion C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_state_quaternion_decode(const mavlink_message_t* msg, mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_state_quaternion->time_usec = mavlink_msg_hil_state_quaternion_get_time_usec(msg); - mavlink_msg_hil_state_quaternion_get_attitude_quaternion(msg, hil_state_quaternion->attitude_quaternion); - hil_state_quaternion->rollspeed = mavlink_msg_hil_state_quaternion_get_rollspeed(msg); - hil_state_quaternion->pitchspeed = mavlink_msg_hil_state_quaternion_get_pitchspeed(msg); - hil_state_quaternion->yawspeed = mavlink_msg_hil_state_quaternion_get_yawspeed(msg); - hil_state_quaternion->lat = mavlink_msg_hil_state_quaternion_get_lat(msg); - hil_state_quaternion->lon = mavlink_msg_hil_state_quaternion_get_lon(msg); - hil_state_quaternion->alt = mavlink_msg_hil_state_quaternion_get_alt(msg); - hil_state_quaternion->vx = mavlink_msg_hil_state_quaternion_get_vx(msg); - hil_state_quaternion->vy = mavlink_msg_hil_state_quaternion_get_vy(msg); - hil_state_quaternion->vz = mavlink_msg_hil_state_quaternion_get_vz(msg); - hil_state_quaternion->ind_airspeed = mavlink_msg_hil_state_quaternion_get_ind_airspeed(msg); - hil_state_quaternion->true_airspeed = mavlink_msg_hil_state_quaternion_get_true_airspeed(msg); - hil_state_quaternion->xacc = mavlink_msg_hil_state_quaternion_get_xacc(msg); - hil_state_quaternion->yacc = mavlink_msg_hil_state_quaternion_get_yacc(msg); - hil_state_quaternion->zacc = mavlink_msg_hil_state_quaternion_get_zacc(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN? msg->len : MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN; - memset(hil_state_quaternion, 0, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); - memcpy(hil_state_quaternion, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_home_position.h b/include/mavlink/v2.0/common/mavlink_msg_home_position.h deleted file mode 100644 index d5ac5e5..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_home_position.h +++ /dev/null @@ -1,430 +0,0 @@ -#pragma once -// MESSAGE HOME_POSITION PACKING - -#define MAVLINK_MSG_ID_HOME_POSITION 242 - -MAVPACKED( -typedef struct __mavlink_home_position_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ - float x; /*< Local X position of this position in the local coordinate frame*/ - float y; /*< Local Y position of this position in the local coordinate frame*/ - float z; /*< Local Z position of this position in the local coordinate frame*/ - float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ - float approach_x; /*< Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_y; /*< Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_z; /*< Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ -}) mavlink_home_position_t; - -#define MAVLINK_MSG_ID_HOME_POSITION_LEN 52 -#define MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN 52 -#define MAVLINK_MSG_ID_242_LEN 52 -#define MAVLINK_MSG_ID_242_MIN_LEN 52 - -#define MAVLINK_MSG_ID_HOME_POSITION_CRC 104 -#define MAVLINK_MSG_ID_242_CRC 104 - -#define MAVLINK_MSG_HOME_POSITION_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HOME_POSITION { \ - 242, \ - "HOME_POSITION", \ - 10, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HOME_POSITION { \ - "HOME_POSITION", \ - 10, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \ - } \ -} -#endif - -/** - * @brief Pack a home_position 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 latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#else - mavlink_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HOME_POSITION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -} - -/** - * @brief Pack a home_position message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#else - mavlink_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HOME_POSITION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -} - -/** - * @brief Encode a home_position struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_home_position_t* home_position) -{ - return mavlink_msg_home_position_pack(system_id, component_id, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z); -} - -/** - * @brief Encode a home_position struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_home_position_t* home_position) -{ - return mavlink_msg_home_position_pack_chan(system_id, component_id, chan, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z); -} - -/** - * @brief Send a home_position message - * @param chan MAVLink channel to send the message - * - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#else - mavlink_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#endif -} - -/** - * @brief Send a home_position message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_home_position_send_struct(mavlink_channel_t chan, const mavlink_home_position_t* home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_home_position_send(chan, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)home_position, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#else - mavlink_home_position_t *packet = (mavlink_home_position_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->x = x; - packet->y = y; - packet->z = z; - packet->approach_x = approach_x; - packet->approach_y = approach_y; - packet->approach_z = approach_z; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HOME_POSITION UNPACKING - - -/** - * @brief Get field latitude from home_position message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from home_position message - * - * @return Longitude (WGS84, in degrees * 1E7 - */ -static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from home_position message - * - * @return Altitude (AMSL), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field x from home_position message - * - * @return Local X position of this position in the local coordinate frame - */ -static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field y from home_position message - * - * @return Local Y position of this position in the local coordinate frame - */ -static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field z from home_position message - * - * @return Local Z position of this position in the local coordinate frame - */ -static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field q from home_position message - * - * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - */ -static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 24); -} - -/** - * @brief Get field approach_x from home_position message - * - * @return Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_home_position_get_approach_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field approach_y from home_position message - * - * @return Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_home_position_get_approach_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field approach_z from home_position message - * - * @return Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_home_position_get_approach_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Decode a home_position message into a struct - * - * @param msg The message to decode - * @param home_position C-struct to decode the message contents into - */ -static inline void mavlink_msg_home_position_decode(const mavlink_message_t* msg, mavlink_home_position_t* home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - home_position->latitude = mavlink_msg_home_position_get_latitude(msg); - home_position->longitude = mavlink_msg_home_position_get_longitude(msg); - home_position->altitude = mavlink_msg_home_position_get_altitude(msg); - home_position->x = mavlink_msg_home_position_get_x(msg); - home_position->y = mavlink_msg_home_position_get_y(msg); - home_position->z = mavlink_msg_home_position_get_z(msg); - mavlink_msg_home_position_get_q(msg, home_position->q); - home_position->approach_x = mavlink_msg_home_position_get_approach_x(msg); - home_position->approach_y = mavlink_msg_home_position_get_approach_y(msg); - home_position->approach_z = mavlink_msg_home_position_get_approach_z(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HOME_POSITION_LEN? msg->len : MAVLINK_MSG_ID_HOME_POSITION_LEN; - memset(home_position, 0, MAVLINK_MSG_ID_HOME_POSITION_LEN); - memcpy(home_position, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_landing_target.h b/include/mavlink/v2.0/common/mavlink_msg_landing_target.h deleted file mode 100644 index c79dc66..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_landing_target.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE LANDING_TARGET PACKING - -#define MAVLINK_MSG_ID_LANDING_TARGET 149 - -MAVPACKED( -typedef struct __mavlink_landing_target_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float angle_x; /*< X-axis angular offset (in radians) of the target from the center of the image*/ - float angle_y; /*< Y-axis angular offset (in radians) of the target from the center of the image*/ - float distance; /*< Distance to the target from the vehicle in meters*/ - float size_x; /*< Size in radians of target along x-axis*/ - float size_y; /*< Size in radians of target along y-axis*/ - uint8_t target_num; /*< The ID of the target if multiple targets are present*/ - uint8_t frame; /*< MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.*/ -}) mavlink_landing_target_t; - -#define MAVLINK_MSG_ID_LANDING_TARGET_LEN 30 -#define MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN 30 -#define MAVLINK_MSG_ID_149_LEN 30 -#define MAVLINK_MSG_ID_149_MIN_LEN 30 - -#define MAVLINK_MSG_ID_LANDING_TARGET_CRC 200 -#define MAVLINK_MSG_ID_149_CRC 200 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \ - 149, \ - "LANDING_TARGET", \ - 8, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \ - { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \ - { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \ - { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \ - { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \ - { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \ - "LANDING_TARGET", \ - 8, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \ - { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \ - { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \ - { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \ - { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \ - { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a landing_target 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 (micros since boot or Unix epoch) - * @param target_num The ID of the target if multiple targets are present - * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - * @param angle_x X-axis angular offset (in radians) of the target from the center of the image - * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image - * @param distance Distance to the target from the vehicle in meters - * @param size_x Size in radians of target along x-axis - * @param size_y Size in radians of target along y-axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#else - mavlink_landing_target_t packet; - packet.time_usec = time_usec; - packet.angle_x = angle_x; - packet.angle_y = angle_y; - packet.distance = distance; - packet.size_x = size_x; - packet.size_y = size_y; - packet.target_num = target_num; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -} - -/** - * @brief Pack a landing_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param target_num The ID of the target if multiple targets are present - * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - * @param angle_x X-axis angular offset (in radians) of the target from the center of the image - * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image - * @param distance Distance to the target from the vehicle in meters - * @param size_x Size in radians of target along x-axis - * @param size_y Size in radians of target along y-axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t target_num,uint8_t frame,float angle_x,float angle_y,float distance,float size_x,float size_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#else - mavlink_landing_target_t packet; - packet.time_usec = time_usec; - packet.angle_x = angle_x; - packet.angle_y = angle_y; - packet.distance = distance; - packet.size_x = size_x; - packet.size_y = size_y; - packet.target_num = target_num; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -} - -/** - * @brief Encode a landing_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param landing_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_landing_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target) -{ - return mavlink_msg_landing_target_pack(system_id, component_id, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y); -} - -/** - * @brief Encode a landing_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param landing_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target) -{ - return mavlink_msg_landing_target_pack_chan(system_id, component_id, chan, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y); -} - -/** - * @brief Send a landing_target message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param target_num The ID of the target if multiple targets are present - * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - * @param angle_x X-axis angular offset (in radians) of the target from the center of the image - * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image - * @param distance Distance to the target from the vehicle in meters - * @param size_x Size in radians of target along x-axis - * @param size_y Size in radians of target along y-axis - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#else - mavlink_landing_target_t packet; - packet.time_usec = time_usec; - packet.angle_x = angle_x; - packet.angle_y = angle_y; - packet.distance = distance; - packet.size_x = size_x; - packet.size_y = size_y; - packet.target_num = target_num; - packet.frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#endif -} - -/** - * @brief Send a landing_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_landing_target_send_struct(mavlink_channel_t chan, const mavlink_landing_target_t* landing_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_landing_target_send(chan, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)landing_target, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LANDING_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#else - mavlink_landing_target_t *packet = (mavlink_landing_target_t *)msgbuf; - packet->time_usec = time_usec; - packet->angle_x = angle_x; - packet->angle_y = angle_y; - packet->distance = distance; - packet->size_x = size_x; - packet->size_y = size_y; - packet->target_num = target_num; - packet->frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LANDING_TARGET UNPACKING - - -/** - * @brief Get field time_usec from landing_target message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_landing_target_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field target_num from landing_target message - * - * @return The ID of the target if multiple targets are present - */ -static inline uint8_t mavlink_msg_landing_target_get_target_num(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field frame from landing_target message - * - * @return MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - */ -static inline uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field angle_x from landing_target message - * - * @return X-axis angular offset (in radians) of the target from the center of the image - */ -static inline float mavlink_msg_landing_target_get_angle_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field angle_y from landing_target message - * - * @return Y-axis angular offset (in radians) of the target from the center of the image - */ -static inline float mavlink_msg_landing_target_get_angle_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field distance from landing_target message - * - * @return Distance to the target from the vehicle in meters - */ -static inline float mavlink_msg_landing_target_get_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field size_x from landing_target message - * - * @return Size in radians of target along x-axis - */ -static inline float mavlink_msg_landing_target_get_size_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field size_y from landing_target message - * - * @return Size in radians of target along y-axis - */ -static inline float mavlink_msg_landing_target_get_size_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a landing_target message into a struct - * - * @param msg The message to decode - * @param landing_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_landing_target_decode(const mavlink_message_t* msg, mavlink_landing_target_t* landing_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - landing_target->time_usec = mavlink_msg_landing_target_get_time_usec(msg); - landing_target->angle_x = mavlink_msg_landing_target_get_angle_x(msg); - landing_target->angle_y = mavlink_msg_landing_target_get_angle_y(msg); - landing_target->distance = mavlink_msg_landing_target_get_distance(msg); - landing_target->size_x = mavlink_msg_landing_target_get_size_x(msg); - landing_target->size_y = mavlink_msg_landing_target_get_size_y(msg); - landing_target->target_num = mavlink_msg_landing_target_get_target_num(msg); - landing_target->frame = mavlink_msg_landing_target_get_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LANDING_TARGET_LEN? msg->len : MAVLINK_MSG_ID_LANDING_TARGET_LEN; - memset(landing_target, 0, MAVLINK_MSG_ID_LANDING_TARGET_LEN); - memcpy(landing_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_local_position_ned.h b/include/mavlink/v2.0/common/mavlink_msg_local_position_ned.h deleted file mode 100644 index 4634032..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_local_position_ned.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE LOCAL_POSITION_NED PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 - -MAVPACKED( -typedef struct __mavlink_local_position_ned_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float x; /*< X Position*/ - float y; /*< Y Position*/ - float z; /*< Z Position*/ - float vx; /*< X Speed*/ - float vy; /*< Y Speed*/ - float vz; /*< Z Speed*/ -}) mavlink_local_position_ned_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN 28 -#define MAVLINK_MSG_ID_32_LEN 28 -#define MAVLINK_MSG_ID_32_MIN_LEN 28 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185 -#define MAVLINK_MSG_ID_32_CRC 185 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ - 32, \ - "LOCAL_POSITION_NED", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ - "LOCAL_POSITION_NED", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ - } \ -} -#endif - -/** - * @brief Pack a local_position_ned 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_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - - 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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -} - -/** - * @brief Pack a local_position_ned message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - - 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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -} - -/** - * @brief Encode a local_position_ned struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) -{ - return mavlink_msg_local_position_ned_pack(system_id, component_id, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); -} - -/** - * @brief Encode a local_position_ned struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) -{ - return mavlink_msg_local_position_ned_pack_chan(system_id, component_id, chan, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); -} - -/** - * @brief Send a local_position_ned message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - mavlink_local_position_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#endif -} - -/** - * @brief Send a local_position_ned message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_local_position_ned_send_struct(mavlink_channel_t chan, const mavlink_local_position_ned_t* local_position_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_local_position_ned_send(chan, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)local_position_ned, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - mavlink_local_position_ned_t *packet = (mavlink_local_position_ned_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_NED UNPACKING - - -/** - * @brief Get field time_boot_ms from local_position_ned message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field x from local_position_ned message - * - * @return X Position - */ -static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from local_position_ned message - * - * @return Y Position - */ -static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from local_position_ned message - * - * @return Z Position - */ -static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from local_position_ned message - * - * @return X Speed - */ -static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from local_position_ned message - * - * @return Y Speed - */ -static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from local_position_ned message - * - * @return Z Speed - */ -static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a local_position_ned message into a struct - * - * @param msg The message to decode - * @param local_position_ned C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_ned_decode(const mavlink_message_t* msg, mavlink_local_position_ned_t* local_position_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - local_position_ned->time_boot_ms = mavlink_msg_local_position_ned_get_time_boot_ms(msg); - local_position_ned->x = mavlink_msg_local_position_ned_get_x(msg); - local_position_ned->y = mavlink_msg_local_position_ned_get_y(msg); - local_position_ned->z = mavlink_msg_local_position_ned_get_z(msg); - local_position_ned->vx = mavlink_msg_local_position_ned_get_vx(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN; - memset(local_position_ned, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); - memcpy(local_position_ned, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_local_position_ned_cov.h b/include/mavlink/v2.0/common/mavlink_msg_local_position_ned_cov.h deleted file mode 100644 index e697e46..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_local_position_ned_cov.h +++ /dev/null @@ -1,480 +0,0 @@ -#pragma once -// MESSAGE LOCAL_POSITION_NED_COV PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64 - -MAVPACKED( -typedef struct __mavlink_local_position_ned_cov_t { - uint64_t time_usec; /*< Timestamp (microseconds since system boot or since UNIX epoch)*/ - float x; /*< X Position*/ - float y; /*< Y Position*/ - float z; /*< Z Position*/ - float vx; /*< X Speed (m/s)*/ - float vy; /*< Y Speed (m/s)*/ - float vz; /*< Z Speed (m/s)*/ - float ax; /*< X Acceleration (m/s^2)*/ - float ay; /*< Y Acceleration (m/s^2)*/ - float az; /*< Z Acceleration (m/s^2)*/ - float covariance[45]; /*< Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)*/ - uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ -}) mavlink_local_position_ned_cov_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 225 -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN 225 -#define MAVLINK_MSG_ID_64_LEN 225 -#define MAVLINK_MSG_ID_64_MIN_LEN 225 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 191 -#define MAVLINK_MSG_ID_64_CRC 191 - -#define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 45 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \ - 64, \ - "LOCAL_POSITION_NED_COV", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vz) }, \ - { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, ax) }, \ - { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \ - { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \ - "LOCAL_POSITION_NED_COV", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vz) }, \ - { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, ax) }, \ - { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \ - { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a local_position_ned_cov 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 since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed (m/s) - * @param vy Y Speed (m/s) - * @param vz Z Speed (m/s) - * @param ax X Acceleration (m/s^2) - * @param ay Y Acceleration (m/s^2) - * @param az Z Acceleration (m/s^2) - * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_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_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#else - mavlink_local_position_ned_cov_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -} - -/** - * @brief Pack a local_position_ned_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed (m/s) - * @param vy Y Speed (m/s) - * @param vz Z Speed (m/s) - * @param ax X Acceleration (m/s^2) - * @param ay Y Acceleration (m/s^2) - * @param az Z Acceleration (m/s^2) - * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t estimator_type,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az,const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_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_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#else - mavlink_local_position_ned_cov_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -} - -/** - * @brief Encode a local_position_ned_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ - return mavlink_msg_local_position_ned_cov_pack(system_id, component_id, msg, local_position_ned_cov->time_usec, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); -} - -/** - * @brief Encode a local_position_ned_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ - return mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, chan, msg, local_position_ned_cov->time_usec, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); -} - -/** - * @brief Send a local_position_ned_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since system boot or since UNIX epoch) - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed (m/s) - * @param vy Y Speed (m/s) - * @param vz Z Speed (m/s) - * @param ax X Acceleration (m/s^2) - * @param ay Y Acceleration (m/s^2) - * @param az Z Acceleration (m/s^2) - * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_local_position_ned_cov_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_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_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#else - mavlink_local_position_ned_cov_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#endif -} - -/** - * @brief Send a local_position_ned_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_local_position_ned_cov_send_struct(mavlink_channel_t chan, const mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_local_position_ned_cov_send(chan, local_position_ned_cov->time_usec, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)local_position_ned_cov, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#else - mavlink_local_position_ned_cov_t *packet = (mavlink_local_position_ned_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->ax = ax; - packet->ay = ay; - packet->az = az; - packet->estimator_type = estimator_type; - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_NED_COV UNPACKING - - -/** - * @brief Get field time_usec from local_position_ned_cov message - * - * @return Timestamp (microseconds since system boot or since UNIX epoch) - */ -static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field estimator_type from local_position_ned_cov message - * - * @return Class id of the estimator this estimate originated from. - */ -static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 224); -} - -/** - * @brief Get field x from local_position_ned_cov message - * - * @return X Position - */ -static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from local_position_ned_cov message - * - * @return Y Position - */ -static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from local_position_ned_cov message - * - * @return Z Position - */ -static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vx from local_position_ned_cov message - * - * @return X Speed (m/s) - */ -static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vy from local_position_ned_cov message - * - * @return Y Speed (m/s) - */ -static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vz from local_position_ned_cov message - * - * @return Z Speed (m/s) - */ -static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field ax from local_position_ned_cov message - * - * @return X Acceleration (m/s^2) - */ -static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ay from local_position_ned_cov message - * - * @return Y Acceleration (m/s^2) - */ -static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field az from local_position_ned_cov message - * - * @return Z Acceleration (m/s^2) - */ -static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field covariance from local_position_ned_cov message - * - * @return Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 45, 44); -} - -/** - * @brief Decode a local_position_ned_cov message into a struct - * - * @param msg The message to decode - * @param local_position_ned_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_ned_cov_decode(const mavlink_message_t* msg, mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - local_position_ned_cov->time_usec = mavlink_msg_local_position_ned_cov_get_time_usec(msg); - local_position_ned_cov->x = mavlink_msg_local_position_ned_cov_get_x(msg); - local_position_ned_cov->y = mavlink_msg_local_position_ned_cov_get_y(msg); - local_position_ned_cov->z = mavlink_msg_local_position_ned_cov_get_z(msg); - local_position_ned_cov->vx = mavlink_msg_local_position_ned_cov_get_vx(msg); - local_position_ned_cov->vy = mavlink_msg_local_position_ned_cov_get_vy(msg); - local_position_ned_cov->vz = mavlink_msg_local_position_ned_cov_get_vz(msg); - local_position_ned_cov->ax = mavlink_msg_local_position_ned_cov_get_ax(msg); - local_position_ned_cov->ay = mavlink_msg_local_position_ned_cov_get_ay(msg); - local_position_ned_cov->az = mavlink_msg_local_position_ned_cov_get_az(msg); - mavlink_msg_local_position_ned_cov_get_covariance(msg, local_position_ned_cov->covariance); - local_position_ned_cov->estimator_type = mavlink_msg_local_position_ned_cov_get_estimator_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN; - memset(local_position_ned_cov, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); - memcpy(local_position_ned_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_local_position_ned_system_global_offset.h b/include/mavlink/v2.0/common/mavlink_msg_local_position_ned_system_global_offset.h deleted file mode 100644 index e87bcaa..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_local_position_ned_system_global_offset.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89 - -MAVPACKED( -typedef struct __mavlink_local_position_ned_system_global_offset_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float x; /*< X Position*/ - float y; /*< Y Position*/ - float z; /*< Z Position*/ - float roll; /*< Roll*/ - float pitch; /*< Pitch*/ - float yaw; /*< Yaw*/ -}) mavlink_local_position_ned_system_global_offset_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28 -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN 28 -#define MAVLINK_MSG_ID_89_LEN 28 -#define MAVLINK_MSG_ID_89_MIN_LEN 28 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231 -#define MAVLINK_MSG_ID_89_CRC 231 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \ - 89, \ - "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_system_global_offset_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_system_global_offset_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_system_global_offset_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_system_global_offset_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_system_global_offset_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_system_global_offset_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_system_global_offset_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \ - "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_system_global_offset_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_system_global_offset_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_system_global_offset_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_system_global_offset_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_system_global_offset_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_system_global_offset_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_system_global_offset_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a local_position_ned_system_global_offset 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_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -} - -/** - * @brief Pack a local_position_ned_system_global_offset message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - - 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; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -} - -/** - * @brief Encode a local_position_ned_system_global_offset struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_system_global_offset C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ - return mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); -} - -/** - * @brief Encode a local_position_ned_system_global_offset struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_system_global_offset C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ - return mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, chan, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); -} - -/** - * @brief Send a local_position_ned_system_global_offset message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - mavlink_local_position_ned_system_global_offset_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - _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_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#endif -} - -/** - * @brief Send a local_position_ned_system_global_offset message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_local_position_ned_system_global_offset_send_struct(mavlink_channel_t chan, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_local_position_ned_system_global_offset_send(chan, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)local_position_ned_system_global_offset, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_ned_system_global_offset_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - mavlink_local_position_ned_system_global_offset_t *packet = (mavlink_local_position_ned_system_global_offset_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - - _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_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET UNPACKING - - -/** - * @brief Get field time_boot_ms from local_position_ned_system_global_offset message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field x from local_position_ned_system_global_offset message - * - * @return X Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from local_position_ned_system_global_offset message - * - * @return Y Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from local_position_ned_system_global_offset message - * - * @return Z Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field roll from local_position_ned_system_global_offset message - * - * @return Roll - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitch from local_position_ned_system_global_offset message - * - * @return Pitch - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yaw from local_position_ned_system_global_offset message - * - * @return Yaw - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a local_position_ned_system_global_offset message into a struct - * - * @param msg The message to decode - * @param local_position_ned_system_global_offset C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_ned_system_global_offset_decode(const mavlink_message_t* msg, mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - local_position_ned_system_global_offset->time_boot_ms = mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(msg); - local_position_ned_system_global_offset->x = mavlink_msg_local_position_ned_system_global_offset_get_x(msg); - local_position_ned_system_global_offset->y = mavlink_msg_local_position_ned_system_global_offset_get_y(msg); - local_position_ned_system_global_offset->z = mavlink_msg_local_position_ned_system_global_offset_get_z(msg); - local_position_ned_system_global_offset->roll = mavlink_msg_local_position_ned_system_global_offset_get_roll(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN; - memset(local_position_ned_system_global_offset, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); - memcpy(local_position_ned_system_global_offset, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_log_data.h b/include/mavlink/v2.0/common/mavlink_msg_log_data.h deleted file mode 100644 index f4adf2f..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_log_data.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE LOG_DATA PACKING - -#define MAVLINK_MSG_ID_LOG_DATA 120 - -MAVPACKED( -typedef struct __mavlink_log_data_t { - uint32_t ofs; /*< Offset into the log*/ - uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ - uint8_t count; /*< Number of bytes (zero for end of log)*/ - uint8_t data[90]; /*< log data*/ -}) mavlink_log_data_t; - -#define MAVLINK_MSG_ID_LOG_DATA_LEN 97 -#define MAVLINK_MSG_ID_LOG_DATA_MIN_LEN 97 -#define MAVLINK_MSG_ID_120_LEN 97 -#define MAVLINK_MSG_ID_120_MIN_LEN 97 - -#define MAVLINK_MSG_ID_LOG_DATA_CRC 134 -#define MAVLINK_MSG_ID_120_CRC 134 - -#define MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN 90 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_DATA { \ - 120, \ - "LOG_DATA", \ - 4, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_DATA { \ - "LOG_DATA", \ - 4, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_data 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 id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -} - -/** - * @brief Pack a log_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t id,uint32_t ofs,uint8_t count,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -} - -/** - * @brief Encode a log_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_data_t* log_data) -{ - return mavlink_msg_log_data_pack(system_id, component_id, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); -} - -/** - * @brief Encode a log_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_data_t* log_data) -{ - return mavlink_msg_log_data_pack_chan(system_id, component_id, chan, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); -} - -/** - * @brief Send a log_data message - * @param chan MAVLink channel to send the message - * - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_data_send(mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#endif -} - -/** - * @brief Send a log_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_data_send_struct(mavlink_channel_t chan, const mavlink_log_data_t* log_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_data_send(chan, log_data->id, log_data->ofs, log_data->count, log_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)log_data, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - mavlink_log_data_t *packet = (mavlink_log_data_t *)msgbuf; - packet->ofs = ofs; - packet->id = id; - packet->count = count; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_DATA UNPACKING - - -/** - * @brief Get field id from log_data message - * - * @return Log id (from LOG_ENTRY reply) - */ -static inline uint16_t mavlink_msg_log_data_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field ofs from log_data message - * - * @return Offset into the log - */ -static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from log_data message - * - * @return Number of bytes (zero for end of log) - */ -static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field data from log_data message - * - * @return log data - */ -static inline uint16_t mavlink_msg_log_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 90, 7); -} - -/** - * @brief Decode a log_data message into a struct - * - * @param msg The message to decode - * @param log_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_data_decode(const mavlink_message_t* msg, mavlink_log_data_t* log_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_data->ofs = mavlink_msg_log_data_get_ofs(msg); - log_data->id = mavlink_msg_log_data_get_id(msg); - log_data->count = mavlink_msg_log_data_get_count(msg); - mavlink_msg_log_data_get_data(msg, log_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_DATA_LEN? msg->len : MAVLINK_MSG_ID_LOG_DATA_LEN; - memset(log_data, 0, MAVLINK_MSG_ID_LOG_DATA_LEN); - memcpy(log_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_log_entry.h b/include/mavlink/v2.0/common/mavlink_msg_log_entry.h deleted file mode 100644 index 733e4e7..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_log_entry.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE LOG_ENTRY PACKING - -#define MAVLINK_MSG_ID_LOG_ENTRY 118 - -MAVPACKED( -typedef struct __mavlink_log_entry_t { - uint32_t time_utc; /*< UTC timestamp of log in seconds since 1970, or 0 if not available*/ - uint32_t size; /*< Size of the log (may be approximate) in bytes*/ - uint16_t id; /*< Log id*/ - uint16_t num_logs; /*< Total number of logs*/ - uint16_t last_log_num; /*< High log number*/ -}) mavlink_log_entry_t; - -#define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 -#define MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN 14 -#define MAVLINK_MSG_ID_118_LEN 14 -#define MAVLINK_MSG_ID_118_MIN_LEN 14 - -#define MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 -#define MAVLINK_MSG_ID_118_CRC 56 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ - 118, \ - "LOG_ENTRY", \ - 5, \ - { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ - { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ - { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ - "LOG_ENTRY", \ - 5, \ - { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ - { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ - { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_entry 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 id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -} - -/** - * @brief Pack a log_entry message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_entry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t id,uint16_t num_logs,uint16_t last_log_num,uint32_t time_utc,uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -} - -/** - * @brief Encode a log_entry struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_entry C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_entry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) -{ - return mavlink_msg_log_entry_pack(system_id, component_id, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); -} - -/** - * @brief Encode a log_entry struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_entry C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_entry_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) -{ - return mavlink_msg_log_entry_pack_chan(system_id, component_id, chan, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); -} - -/** - * @brief Send a log_entry message - * @param chan MAVLink channel to send the message - * - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_entry_send(mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#endif -} - -/** - * @brief Send a log_entry message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_entry_send_struct(mavlink_channel_t chan, const mavlink_log_entry_t* log_entry) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_entry_send(chan, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)log_entry, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_ENTRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_entry_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - mavlink_log_entry_t *packet = (mavlink_log_entry_t *)msgbuf; - packet->time_utc = time_utc; - packet->size = size; - packet->id = id; - packet->num_logs = num_logs; - packet->last_log_num = last_log_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_ENTRY UNPACKING - - -/** - * @brief Get field id from log_entry message - * - * @return Log id - */ -static inline uint16_t mavlink_msg_log_entry_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field num_logs from log_entry message - * - * @return Total number of logs - */ -static inline uint16_t mavlink_msg_log_entry_get_num_logs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field last_log_num from log_entry message - * - * @return High log number - */ -static inline uint16_t mavlink_msg_log_entry_get_last_log_num(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field time_utc from log_entry message - * - * @return UTC timestamp of log in seconds since 1970, or 0 if not available - */ -static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field size from log_entry message - * - * @return Size of the log (may be approximate) in bytes - */ -static inline uint32_t mavlink_msg_log_entry_get_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Decode a log_entry message into a struct - * - * @param msg The message to decode - * @param log_entry C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_entry_decode(const mavlink_message_t* msg, mavlink_log_entry_t* log_entry) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_entry->time_utc = mavlink_msg_log_entry_get_time_utc(msg); - log_entry->size = mavlink_msg_log_entry_get_size(msg); - log_entry->id = mavlink_msg_log_entry_get_id(msg); - log_entry->num_logs = mavlink_msg_log_entry_get_num_logs(msg); - log_entry->last_log_num = mavlink_msg_log_entry_get_last_log_num(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_ENTRY_LEN? msg->len : MAVLINK_MSG_ID_LOG_ENTRY_LEN; - memset(log_entry, 0, MAVLINK_MSG_ID_LOG_ENTRY_LEN); - memcpy(log_entry, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_log_erase.h b/include/mavlink/v2.0/common/mavlink_msg_log_erase.h deleted file mode 100644 index d603771..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_log_erase.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE LOG_ERASE PACKING - -#define MAVLINK_MSG_ID_LOG_ERASE 121 - -MAVPACKED( -typedef struct __mavlink_log_erase_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_erase_t; - -#define MAVLINK_MSG_ID_LOG_ERASE_LEN 2 -#define MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN 2 -#define MAVLINK_MSG_ID_121_LEN 2 -#define MAVLINK_MSG_ID_121_MIN_LEN 2 - -#define MAVLINK_MSG_ID_LOG_ERASE_CRC 237 -#define MAVLINK_MSG_ID_121_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_ERASE { \ - 121, \ - "LOG_ERASE", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_erase_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_erase_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_ERASE { \ - "LOG_ERASE", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_erase_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_erase_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_erase message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_erase_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -} - -/** - * @brief Pack a log_erase message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_erase_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -} - -/** - * @brief Encode a log_erase struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_erase C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_erase_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) -{ - return mavlink_msg_log_erase_pack(system_id, component_id, msg, log_erase->target_system, log_erase->target_component); -} - -/** - * @brief Encode a log_erase struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_erase C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_erase_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) -{ - return mavlink_msg_log_erase_pack_chan(system_id, component_id, chan, msg, log_erase->target_system, log_erase->target_component); -} - -/** - * @brief Send a log_erase message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_erase_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_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_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#endif -} - -/** - * @brief Send a log_erase message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_erase_send_struct(mavlink_channel_t chan, const mavlink_log_erase_t* log_erase) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_erase_send(chan, log_erase->target_system, log_erase->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)log_erase, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_ERASE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_erase_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - mavlink_log_erase_t *packet = (mavlink_log_erase_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_ERASE UNPACKING - - -/** - * @brief Get field target_system from log_erase message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_erase_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from log_erase message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_erase_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a log_erase message into a struct - * - * @param msg The message to decode - * @param log_erase C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_erase_decode(const mavlink_message_t* msg, mavlink_log_erase_t* log_erase) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_erase->target_system = mavlink_msg_log_erase_get_target_system(msg); - log_erase->target_component = mavlink_msg_log_erase_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_ERASE_LEN? msg->len : MAVLINK_MSG_ID_LOG_ERASE_LEN; - memset(log_erase, 0, MAVLINK_MSG_ID_LOG_ERASE_LEN); - memcpy(log_erase, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_log_request_data.h b/include/mavlink/v2.0/common/mavlink_msg_log_request_data.h deleted file mode 100644 index 3fb3d62..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_log_request_data.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE LOG_REQUEST_DATA PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119 - -MAVPACKED( -typedef struct __mavlink_log_request_data_t { - uint32_t ofs; /*< Offset into the log*/ - uint32_t count; /*< Number of bytes*/ - uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_request_data_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12 -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN 12 -#define MAVLINK_MSG_ID_119_LEN 12 -#define MAVLINK_MSG_ID_119_MIN_LEN 12 - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116 -#define MAVLINK_MSG_ID_119_CRC 116 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \ - 119, \ - "LOG_REQUEST_DATA", \ - 5, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ - { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \ - "LOG_REQUEST_DATA", \ - 5, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ - { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_request_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -} - -/** - * @brief Pack a log_request_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t id,uint32_t ofs,uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -} - -/** - * @brief Encode a log_request_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) -{ - return mavlink_msg_log_request_data_pack(system_id, component_id, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); -} - -/** - * @brief Encode a log_request_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) -{ - return mavlink_msg_log_request_data_pack_chan(system_id, component_id, chan, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); -} - -/** - * @brief Send a log_request_data message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#endif -} - -/** - * @brief Send a log_request_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_request_data_send_struct(mavlink_channel_t chan, const mavlink_log_request_data_t* log_request_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_request_data_send(chan, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)log_request_data, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - mavlink_log_request_data_t *packet = (mavlink_log_request_data_t *)msgbuf; - packet->ofs = ofs; - packet->count = count; - packet->id = id; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_DATA UNPACKING - - -/** - * @brief Get field target_system from log_request_data message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_data_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field target_component from log_request_data message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_data_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field id from log_request_data message - * - * @return Log id (from LOG_ENTRY reply) - */ -static inline uint16_t mavlink_msg_log_request_data_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field ofs from log_request_data message - * - * @return Offset into the log - */ -static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from log_request_data message - * - * @return Number of bytes - */ -static inline uint32_t mavlink_msg_log_request_data_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Decode a log_request_data message into a struct - * - * @param msg The message to decode - * @param log_request_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_data_decode(const mavlink_message_t* msg, mavlink_log_request_data_t* log_request_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_request_data->ofs = mavlink_msg_log_request_data_get_ofs(msg); - log_request_data->count = mavlink_msg_log_request_data_get_count(msg); - log_request_data->id = mavlink_msg_log_request_data_get_id(msg); - log_request_data->target_system = mavlink_msg_log_request_data_get_target_system(msg); - log_request_data->target_component = mavlink_msg_log_request_data_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN? msg->len : MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN; - memset(log_request_data, 0, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); - memcpy(log_request_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_log_request_end.h b/include/mavlink/v2.0/common/mavlink_msg_log_request_end.h deleted file mode 100644 index dc0c1e5..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_log_request_end.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE LOG_REQUEST_END PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_END 122 - -MAVPACKED( -typedef struct __mavlink_log_request_end_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_request_end_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2 -#define MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN 2 -#define MAVLINK_MSG_ID_122_LEN 2 -#define MAVLINK_MSG_ID_122_MIN_LEN 2 - -#define MAVLINK_MSG_ID_LOG_REQUEST_END_CRC 203 -#define MAVLINK_MSG_ID_122_CRC 203 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_END { \ - 122, \ - "LOG_REQUEST_END", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_request_end_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_request_end_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_END { \ - "LOG_REQUEST_END", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_request_end_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_request_end_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_request_end message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_end_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -} - -/** - * @brief Pack a log_request_end message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_end_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -} - -/** - * @brief Encode a log_request_end struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_end C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_end_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) -{ - return mavlink_msg_log_request_end_pack(system_id, component_id, msg, log_request_end->target_system, log_request_end->target_component); -} - -/** - * @brief Encode a log_request_end struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_end C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_end_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) -{ - return mavlink_msg_log_request_end_pack_chan(system_id, component_id, chan, msg, log_request_end->target_system, log_request_end->target_component); -} - -/** - * @brief Send a log_request_end message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_end_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_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_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#endif -} - -/** - * @brief Send a log_request_end message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_request_end_send_struct(mavlink_channel_t chan, const mavlink_log_request_end_t* log_request_end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_request_end_send(chan, log_request_end->target_system, log_request_end->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)log_request_end, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_END_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_end_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - mavlink_log_request_end_t *packet = (mavlink_log_request_end_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_END UNPACKING - - -/** - * @brief Get field target_system from log_request_end message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_end_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from log_request_end message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_end_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a log_request_end message into a struct - * - * @param msg The message to decode - * @param log_request_end C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_end_decode(const mavlink_message_t* msg, mavlink_log_request_end_t* log_request_end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_request_end->target_system = mavlink_msg_log_request_end_get_target_system(msg); - log_request_end->target_component = mavlink_msg_log_request_end_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_REQUEST_END_LEN? msg->len : MAVLINK_MSG_ID_LOG_REQUEST_END_LEN; - memset(log_request_end, 0, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); - memcpy(log_request_end, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_log_request_list.h b/include/mavlink/v2.0/common/mavlink_msg_log_request_list.h deleted file mode 100644 index f4b00c9..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_log_request_list.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE LOG_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST 117 - -MAVPACKED( -typedef struct __mavlink_log_request_list_t { - uint16_t start; /*< First log id (0 for first available)*/ - uint16_t end; /*< Last log id (0xffff for last available)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_log_request_list_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6 -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN 6 -#define MAVLINK_MSG_ID_117_LEN 6 -#define MAVLINK_MSG_ID_117_MIN_LEN 6 - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC 128 -#define MAVLINK_MSG_ID_117_CRC 128 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \ - 117, \ - "LOG_REQUEST_LIST", \ - 4, \ - { { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ - { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \ - "LOG_REQUEST_LIST", \ - 4, \ - { { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ - { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -} - -/** - * @brief Pack a log_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t start,uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -} - -/** - * @brief Encode a log_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) -{ - return mavlink_msg_log_request_list_pack(system_id, component_id, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); -} - -/** - * @brief Encode a log_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) -{ - return mavlink_msg_log_request_list_pack_chan(system_id, component_id, chan, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); -} - -/** - * @brief Send a log_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _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_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#endif -} - -/** - * @brief Send a log_request_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_request_list_send_struct(mavlink_channel_t chan, const mavlink_log_request_list_t* log_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_request_list_send(chan, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)log_request_list, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _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_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - mavlink_log_request_list_t *packet = (mavlink_log_request_list_t *)msgbuf; - packet->start = start; - packet->end = end; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from log_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from log_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start from log_request_list message - * - * @return First log id (0 for first available) - */ -static inline uint16_t mavlink_msg_log_request_list_get_start(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field end from log_request_list message - * - * @return Last log id (0xffff for last available) - */ -static inline uint16_t mavlink_msg_log_request_list_get_end(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a log_request_list message into a struct - * - * @param msg The message to decode - * @param log_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_list_decode(const mavlink_message_t* msg, mavlink_log_request_list_t* log_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_request_list->start = mavlink_msg_log_request_list_get_start(msg); - log_request_list->end = mavlink_msg_log_request_list_get_end(msg); - log_request_list->target_system = mavlink_msg_log_request_list_get_target_system(msg); - log_request_list->target_component = mavlink_msg_log_request_list_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN; - memset(log_request_list, 0, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); - memcpy(log_request_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_logging_ack.h b/include/mavlink/v2.0/common/mavlink_msg_logging_ack.h deleted file mode 100644 index c0cbb86..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_logging_ack.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE LOGGING_ACK PACKING - -#define MAVLINK_MSG_ID_LOGGING_ACK 268 - -MAVPACKED( -typedef struct __mavlink_logging_ack_t { - uint16_t sequence; /*< sequence number (must match the one in LOGGING_DATA_ACKED)*/ - uint8_t target_system; /*< system ID of the target*/ - uint8_t target_component; /*< component ID of the target*/ -}) mavlink_logging_ack_t; - -#define MAVLINK_MSG_ID_LOGGING_ACK_LEN 4 -#define MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN 4 -#define MAVLINK_MSG_ID_268_LEN 4 -#define MAVLINK_MSG_ID_268_MIN_LEN 4 - -#define MAVLINK_MSG_ID_LOGGING_ACK_CRC 14 -#define MAVLINK_MSG_ID_268_CRC 14 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOGGING_ACK { \ - 268, \ - "LOGGING_ACK", \ - 3, \ - { { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_ack_t, sequence) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_ack_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOGGING_ACK { \ - "LOGGING_ACK", \ - 3, \ - { { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_ack_t, sequence) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_ack_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a logging_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (must match the one in LOGGING_DATA_ACKED) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_ACK_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_ACK_LEN); -#else - mavlink_logging_ack_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_ACK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -} - -/** - * @brief Pack a logging_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (must match the one in LOGGING_DATA_ACKED) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_ACK_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_ACK_LEN); -#else - mavlink_logging_ack_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -} - -/** - * @brief Encode a logging_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param logging_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logging_ack_t* logging_ack) -{ - return mavlink_msg_logging_ack_pack(system_id, component_id, msg, logging_ack->target_system, logging_ack->target_component, logging_ack->sequence); -} - -/** - * @brief Encode a logging_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param logging_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logging_ack_t* logging_ack) -{ - return mavlink_msg_logging_ack_pack_chan(system_id, component_id, chan, msg, logging_ack->target_system, logging_ack->target_component, logging_ack->sequence); -} - -/** - * @brief Send a logging_ack message - * @param chan MAVLink channel to send the message - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (must match the one in LOGGING_DATA_ACKED) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_logging_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_ACK_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _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_LOGGING_ACK, buf, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -#else - mavlink_logging_ack_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, (const char *)&packet, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -#endif -} - -/** - * @brief Send a logging_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_logging_ack_send_struct(mavlink_channel_t chan, const mavlink_logging_ack_t* logging_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_logging_ack_send(chan, logging_ack->target_system, logging_ack->target_component, logging_ack->sequence); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, (const char *)logging_ack, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOGGING_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_logging_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, sequence); - _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_LOGGING_ACK, buf, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -#else - mavlink_logging_ack_t *packet = (mavlink_logging_ack_t *)msgbuf; - packet->sequence = sequence; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, (const char *)packet, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOGGING_ACK UNPACKING - - -/** - * @brief Get field target_system from logging_ack message - * - * @return system ID of the target - */ -static inline uint8_t mavlink_msg_logging_ack_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from logging_ack message - * - * @return component ID of the target - */ -static inline uint8_t mavlink_msg_logging_ack_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field sequence from logging_ack message - * - * @return sequence number (must match the one in LOGGING_DATA_ACKED) - */ -static inline uint16_t mavlink_msg_logging_ack_get_sequence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a logging_ack message into a struct - * - * @param msg The message to decode - * @param logging_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_logging_ack_decode(const mavlink_message_t* msg, mavlink_logging_ack_t* logging_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - logging_ack->sequence = mavlink_msg_logging_ack_get_sequence(msg); - logging_ack->target_system = mavlink_msg_logging_ack_get_target_system(msg); - logging_ack->target_component = mavlink_msg_logging_ack_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGING_ACK_LEN? msg->len : MAVLINK_MSG_ID_LOGGING_ACK_LEN; - memset(logging_ack, 0, MAVLINK_MSG_ID_LOGGING_ACK_LEN); - memcpy(logging_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_logging_data.h b/include/mavlink/v2.0/common/mavlink_msg_logging_data.h deleted file mode 100644 index 0b6943a..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_logging_data.h +++ /dev/null @@ -1,330 +0,0 @@ -#pragma once -// MESSAGE LOGGING_DATA PACKING - -#define MAVLINK_MSG_ID_LOGGING_DATA 266 - -MAVPACKED( -typedef struct __mavlink_logging_data_t { - uint16_t sequence; /*< sequence number (can wrap)*/ - uint8_t target_system; /*< system ID of the target*/ - uint8_t target_component; /*< component ID of the target*/ - uint8_t length; /*< data length*/ - uint8_t first_message_offset; /*< offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).*/ - uint8_t data[249]; /*< logged data*/ -}) mavlink_logging_data_t; - -#define MAVLINK_MSG_ID_LOGGING_DATA_LEN 255 -#define MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN 255 -#define MAVLINK_MSG_ID_266_LEN 255 -#define MAVLINK_MSG_ID_266_MIN_LEN 255 - -#define MAVLINK_MSG_ID_LOGGING_DATA_CRC 193 -#define MAVLINK_MSG_ID_266_CRC 193 - -#define MAVLINK_MSG_LOGGING_DATA_FIELD_DATA_LEN 249 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOGGING_DATA { \ - 266, \ - "LOGGING_DATA", \ - 6, \ - { { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_t, sequence) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_t, target_component) }, \ - { "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_t, length) }, \ - { "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_t, first_message_offset) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOGGING_DATA { \ - "LOGGING_DATA", \ - 6, \ - { { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_t, sequence) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_t, target_component) }, \ - { "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_t, length) }, \ - { "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_t, first_message_offset) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a logging_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length data length - * @param first_message_offset offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - * @param data logged data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_LEN); -#else - mavlink_logging_data_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -} - -/** - * @brief Pack a logging_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length data length - * @param first_message_offset offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - * @param data logged data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t sequence,uint8_t length,uint8_t first_message_offset,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_LEN); -#else - mavlink_logging_data_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -} - -/** - * @brief Encode a logging_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param logging_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logging_data_t* logging_data) -{ - return mavlink_msg_logging_data_pack(system_id, component_id, msg, logging_data->target_system, logging_data->target_component, logging_data->sequence, logging_data->length, logging_data->first_message_offset, logging_data->data); -} - -/** - * @brief Encode a logging_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param logging_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logging_data_t* logging_data) -{ - return mavlink_msg_logging_data_pack_chan(system_id, component_id, chan, msg, logging_data->target_system, logging_data->target_component, logging_data->sequence, logging_data->length, logging_data->first_message_offset, logging_data->data); -} - -/** - * @brief Send a logging_data message - * @param chan MAVLink channel to send the message - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length data length - * @param first_message_offset offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - * @param data logged data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_logging_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, buf, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -#else - mavlink_logging_data_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -#endif -} - -/** - * @brief Send a logging_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_logging_data_send_struct(mavlink_channel_t chan, const mavlink_logging_data_t* logging_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_logging_data_send(chan, logging_data->target_system, logging_data->target_component, logging_data->sequence, logging_data->length, logging_data->first_message_offset, logging_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, (const char *)logging_data, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOGGING_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_logging_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, buf, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -#else - mavlink_logging_data_t *packet = (mavlink_logging_data_t *)msgbuf; - packet->sequence = sequence; - packet->target_system = target_system; - packet->target_component = target_component; - packet->length = length; - packet->first_message_offset = first_message_offset; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, (const char *)packet, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOGGING_DATA UNPACKING - - -/** - * @brief Get field target_system from logging_data message - * - * @return system ID of the target - */ -static inline uint8_t mavlink_msg_logging_data_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from logging_data message - * - * @return component ID of the target - */ -static inline uint8_t mavlink_msg_logging_data_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field sequence from logging_data message - * - * @return sequence number (can wrap) - */ -static inline uint16_t mavlink_msg_logging_data_get_sequence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field length from logging_data message - * - * @return data length - */ -static inline uint8_t mavlink_msg_logging_data_get_length(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field first_message_offset from logging_data message - * - * @return offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - */ -static inline uint8_t mavlink_msg_logging_data_get_first_message_offset(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field data from logging_data message - * - * @return logged data - */ -static inline uint16_t mavlink_msg_logging_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 249, 6); -} - -/** - * @brief Decode a logging_data message into a struct - * - * @param msg The message to decode - * @param logging_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_logging_data_decode(const mavlink_message_t* msg, mavlink_logging_data_t* logging_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - logging_data->sequence = mavlink_msg_logging_data_get_sequence(msg); - logging_data->target_system = mavlink_msg_logging_data_get_target_system(msg); - logging_data->target_component = mavlink_msg_logging_data_get_target_component(msg); - logging_data->length = mavlink_msg_logging_data_get_length(msg); - logging_data->first_message_offset = mavlink_msg_logging_data_get_first_message_offset(msg); - mavlink_msg_logging_data_get_data(msg, logging_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGING_DATA_LEN? msg->len : MAVLINK_MSG_ID_LOGGING_DATA_LEN; - memset(logging_data, 0, MAVLINK_MSG_ID_LOGGING_DATA_LEN); - memcpy(logging_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_logging_data_acked.h b/include/mavlink/v2.0/common/mavlink_msg_logging_data_acked.h deleted file mode 100644 index 32dea17..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_logging_data_acked.h +++ /dev/null @@ -1,330 +0,0 @@ -#pragma once -// MESSAGE LOGGING_DATA_ACKED PACKING - -#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED 267 - -MAVPACKED( -typedef struct __mavlink_logging_data_acked_t { - uint16_t sequence; /*< sequence number (can wrap)*/ - uint8_t target_system; /*< system ID of the target*/ - uint8_t target_component; /*< component ID of the target*/ - uint8_t length; /*< data length*/ - uint8_t first_message_offset; /*< offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).*/ - uint8_t data[249]; /*< logged data*/ -}) mavlink_logging_data_acked_t; - -#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN 255 -#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN 255 -#define MAVLINK_MSG_ID_267_LEN 255 -#define MAVLINK_MSG_ID_267_MIN_LEN 255 - -#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC 35 -#define MAVLINK_MSG_ID_267_CRC 35 - -#define MAVLINK_MSG_LOGGING_DATA_ACKED_FIELD_DATA_LEN 249 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED { \ - 267, \ - "LOGGING_DATA_ACKED", \ - 6, \ - { { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_acked_t, sequence) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_acked_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_acked_t, target_component) }, \ - { "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_acked_t, length) }, \ - { "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_acked_t, first_message_offset) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_acked_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED { \ - "LOGGING_DATA_ACKED", \ - 6, \ - { { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_acked_t, sequence) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_acked_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_acked_t, target_component) }, \ - { "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_acked_t, length) }, \ - { "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_acked_t, first_message_offset) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_acked_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a logging_data_acked message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length data length - * @param first_message_offset offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - * @param data logged data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_data_acked_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN); -#else - mavlink_logging_data_acked_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA_ACKED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -} - -/** - * @brief Pack a logging_data_acked message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length data length - * @param first_message_offset offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - * @param data logged data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_data_acked_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t sequence,uint8_t length,uint8_t first_message_offset,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN); -#else - mavlink_logging_data_acked_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA_ACKED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -} - -/** - * @brief Encode a logging_data_acked struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param logging_data_acked C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_data_acked_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logging_data_acked_t* logging_data_acked) -{ - return mavlink_msg_logging_data_acked_pack(system_id, component_id, msg, logging_data_acked->target_system, logging_data_acked->target_component, logging_data_acked->sequence, logging_data_acked->length, logging_data_acked->first_message_offset, logging_data_acked->data); -} - -/** - * @brief Encode a logging_data_acked struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param logging_data_acked C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_data_acked_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logging_data_acked_t* logging_data_acked) -{ - return mavlink_msg_logging_data_acked_pack_chan(system_id, component_id, chan, msg, logging_data_acked->target_system, logging_data_acked->target_component, logging_data_acked->sequence, logging_data_acked->length, logging_data_acked->first_message_offset, logging_data_acked->data); -} - -/** - * @brief Send a logging_data_acked message - * @param chan MAVLink channel to send the message - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length data length - * @param first_message_offset offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - * @param data logged data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_logging_data_acked_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -#else - mavlink_logging_data_acked_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, (const char *)&packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -#endif -} - -/** - * @brief Send a logging_data_acked message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_logging_data_acked_send_struct(mavlink_channel_t chan, const mavlink_logging_data_acked_t* logging_data_acked) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_logging_data_acked_send(chan, logging_data_acked->target_system, logging_data_acked->target_component, logging_data_acked->sequence, logging_data_acked->length, logging_data_acked->first_message_offset, logging_data_acked->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, (const char *)logging_data_acked, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_logging_data_acked_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -#else - mavlink_logging_data_acked_t *packet = (mavlink_logging_data_acked_t *)msgbuf; - packet->sequence = sequence; - packet->target_system = target_system; - packet->target_component = target_component; - packet->length = length; - packet->first_message_offset = first_message_offset; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, (const char *)packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOGGING_DATA_ACKED UNPACKING - - -/** - * @brief Get field target_system from logging_data_acked message - * - * @return system ID of the target - */ -static inline uint8_t mavlink_msg_logging_data_acked_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from logging_data_acked message - * - * @return component ID of the target - */ -static inline uint8_t mavlink_msg_logging_data_acked_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field sequence from logging_data_acked message - * - * @return sequence number (can wrap) - */ -static inline uint16_t mavlink_msg_logging_data_acked_get_sequence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field length from logging_data_acked message - * - * @return data length - */ -static inline uint8_t mavlink_msg_logging_data_acked_get_length(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field first_message_offset from logging_data_acked message - * - * @return offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - */ -static inline uint8_t mavlink_msg_logging_data_acked_get_first_message_offset(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field data from logging_data_acked message - * - * @return logged data - */ -static inline uint16_t mavlink_msg_logging_data_acked_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 249, 6); -} - -/** - * @brief Decode a logging_data_acked message into a struct - * - * @param msg The message to decode - * @param logging_data_acked C-struct to decode the message contents into - */ -static inline void mavlink_msg_logging_data_acked_decode(const mavlink_message_t* msg, mavlink_logging_data_acked_t* logging_data_acked) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - logging_data_acked->sequence = mavlink_msg_logging_data_acked_get_sequence(msg); - logging_data_acked->target_system = mavlink_msg_logging_data_acked_get_target_system(msg); - logging_data_acked->target_component = mavlink_msg_logging_data_acked_get_target_component(msg); - logging_data_acked->length = mavlink_msg_logging_data_acked_get_length(msg); - logging_data_acked->first_message_offset = mavlink_msg_logging_data_acked_get_first_message_offset(msg); - mavlink_msg_logging_data_acked_get_data(msg, logging_data_acked->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN? msg->len : MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN; - memset(logging_data_acked, 0, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN); - memcpy(logging_data_acked, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_manual_control.h b/include/mavlink/v2.0/common/mavlink_msg_manual_control.h deleted file mode 100644 index 05a2566..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_manual_control.h +++ /dev/null @@ -1,338 +0,0 @@ -#pragma once -// MESSAGE MANUAL_CONTROL PACKING - -#define MAVLINK_MSG_ID_MANUAL_CONTROL 69 - -MAVPACKED( -typedef struct __mavlink_manual_control_t { - int16_t x; /*< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.*/ - int16_t y; /*< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.*/ - int16_t z; /*< Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.*/ - int16_t r; /*< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.*/ - uint16_t buttons; /*< A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.*/ - uint8_t target; /*< The system to be controlled.*/ -}) mavlink_manual_control_t; - -#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11 -#define MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN 11 -#define MAVLINK_MSG_ID_69_LEN 11 -#define MAVLINK_MSG_ID_69_MIN_LEN 11 - -#define MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243 -#define MAVLINK_MSG_ID_69_CRC 243 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ - 69, \ - "MANUAL_CONTROL", \ - 6, \ - { { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \ - { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \ - { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \ - { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ - "MANUAL_CONTROL", \ - 6, \ - { { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \ - { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \ - { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \ - { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ - } \ -} -#endif - -/** - * @brief Pack a manual_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - - 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, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -} - -/** - * @brief Pack a manual_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - - 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, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -} - -/** - * @brief Encode a manual_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param manual_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) -{ - return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); -} - -/** - * @brief Encode a manual_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param manual_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) -{ - return mavlink_msg_manual_control_pack_chan(system_id, component_id, chan, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); -} - -/** - * @brief Send a manual_control message - * @param chan MAVLink channel to send the message - * - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int16_t(buf, 6, r); - _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, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#endif -} - -/** - * @brief Send a manual_control message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_manual_control_send_struct(mavlink_channel_t chan, const mavlink_manual_control_t* manual_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_manual_control_send(chan, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)manual_control, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MANUAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_manual_control_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_int16_t(buf, 0, x); - _mav_put_int16_t(buf, 2, y); - _mav_put_int16_t(buf, 4, z); - _mav_put_int16_t(buf, 6, r); - _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, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - mavlink_manual_control_t *packet = (mavlink_manual_control_t *)msgbuf; - packet->x = x; - packet->y = y; - packet->z = z; - packet->r = r; - packet->buttons = buttons; - packet->target = target; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MANUAL_CONTROL UNPACKING - - -/** - * @brief Get field target from manual_control message - * - * @return The system to be controlled. - */ -static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field x from manual_control message - * - * @return X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field y from manual_control message - * - * @return Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Get field z from manual_control message - * - * @return Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - */ -static inline int16_t mavlink_msg_manual_control_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field r from manual_control message - * - * @return R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_r(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field buttons from manual_control message - * - * @return A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - */ -static inline uint16_t mavlink_msg_manual_control_get_buttons(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Decode a manual_control message into a struct - * - * @param msg The message to decode - * @param manual_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - manual_control->x = mavlink_msg_manual_control_get_x(msg); - manual_control->y = mavlink_msg_manual_control_get_y(msg); - manual_control->z = mavlink_msg_manual_control_get_z(msg); - manual_control->r = mavlink_msg_manual_control_get_r(msg); - manual_control->buttons = mavlink_msg_manual_control_get_buttons(msg); - manual_control->target = mavlink_msg_manual_control_get_target(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MANUAL_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_MANUAL_CONTROL_LEN; - memset(manual_control, 0, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); - memcpy(manual_control, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_manual_setpoint.h b/include/mavlink/v2.0/common/mavlink_msg_manual_setpoint.h deleted file mode 100644 index 04d50a8..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_manual_setpoint.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE MANUAL_SETPOINT PACKING - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT 81 - -MAVPACKED( -typedef struct __mavlink_manual_setpoint_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float roll; /*< Desired roll rate in radians per second*/ - float pitch; /*< Desired pitch rate in radians per second*/ - float yaw; /*< Desired yaw rate in radians per second*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1*/ - uint8_t mode_switch; /*< Flight mode switch position, 0.. 255*/ - uint8_t manual_override_switch; /*< Override mode switch position, 0.. 255*/ -}) mavlink_manual_setpoint_t; - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22 -#define MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN 22 -#define MAVLINK_MSG_ID_81_LEN 22 -#define MAVLINK_MSG_ID_81_MIN_LEN 22 - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC 106 -#define MAVLINK_MSG_ID_81_CRC 106 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \ - 81, \ - "MANUAL_SETPOINT", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \ - { "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \ - { "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \ - "MANUAL_SETPOINT", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \ - { "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \ - { "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \ - } \ -} -#endif - -/** - * @brief Pack a manual_setpoint 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_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - - 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; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.mode_switch = mode_switch; - packet.manual_override_switch = manual_override_switch; - - 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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -} - -/** - * @brief Pack a manual_setpoint message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - - 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; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.mode_switch = mode_switch; - packet.manual_override_switch = manual_override_switch; - - 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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -} - -/** - * @brief Encode a manual_setpoint struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param manual_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) -{ - return mavlink_msg_manual_setpoint_pack(system_id, component_id, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); -} - -/** - * @brief Encode a manual_setpoint struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param manual_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) -{ - return mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, chan, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); -} - -/** - * @brief Send a manual_setpoint message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - mavlink_manual_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - 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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#endif -} - -/** - * @brief Send a manual_setpoint message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_manual_setpoint_send_struct(mavlink_channel_t chan, const mavlink_manual_setpoint_t* manual_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_manual_setpoint_send(chan, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)manual_setpoint, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_manual_setpoint_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - mavlink_manual_setpoint_t *packet = (mavlink_manual_setpoint_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->thrust = thrust; - 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, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MANUAL_SETPOINT UNPACKING - - -/** - * @brief Get field time_boot_ms from manual_setpoint message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll from manual_setpoint message - * - * @return Desired roll rate in radians per second - */ -static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch from manual_setpoint message - * - * @return Desired pitch rate in radians per second - */ -static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from manual_setpoint message - * - * @return Desired yaw rate in radians per second - */ -static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field thrust from manual_setpoint message - * - * @return Collective thrust, normalized to 0 .. 1 - */ -static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field mode_switch from manual_setpoint message - * - * @return Flight mode switch position, 0.. 255 - */ -static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field manual_override_switch from manual_setpoint message - * - * @return Override mode switch position, 0.. 255 - */ -static inline uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a manual_setpoint message into a struct - * - * @param msg The message to decode - * @param manual_setpoint C-struct to decode the message contents into - */ -static inline void mavlink_msg_manual_setpoint_decode(const mavlink_message_t* msg, mavlink_manual_setpoint_t* manual_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - manual_setpoint->time_boot_ms = mavlink_msg_manual_setpoint_get_time_boot_ms(msg); - manual_setpoint->roll = mavlink_msg_manual_setpoint_get_roll(msg); - manual_setpoint->pitch = mavlink_msg_manual_setpoint_get_pitch(msg); - manual_setpoint->yaw = mavlink_msg_manual_setpoint_get_yaw(msg); - manual_setpoint->thrust = mavlink_msg_manual_setpoint_get_thrust(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN? msg->len : MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN; - memset(manual_setpoint, 0, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); - memcpy(manual_setpoint, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_memory_vect.h b/include/mavlink/v2.0/common/mavlink_msg_memory_vect.h deleted file mode 100644 index efc0e62..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_memory_vect.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE MEMORY_VECT PACKING - -#define MAVLINK_MSG_ID_MEMORY_VECT 249 - -MAVPACKED( -typedef struct __mavlink_memory_vect_t { - uint16_t address; /*< Starting address of the debug variables*/ - uint8_t ver; /*< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below*/ - uint8_t type; /*< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14*/ - int8_t value[32]; /*< Memory contents at specified address*/ -}) mavlink_memory_vect_t; - -#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 -#define MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN 36 -#define MAVLINK_MSG_ID_249_LEN 36 -#define MAVLINK_MSG_ID_249_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ - 249, \ - "MEMORY_VECT", \ - 4, \ - { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ - { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ - { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ - "MEMORY_VECT", \ - 4, \ - { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ - { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ - { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ - } \ -} -#endif - -/** - * @brief Pack a memory_vect 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 address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -} - -/** - * @brief Pack a memory_vect message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t address,uint8_t ver,uint8_t type,const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -} - -/** - * @brief Encode a memory_vect struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param memory_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) -{ - return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); -} - -/** - * @brief Encode a memory_vect struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param memory_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_memory_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) -{ - return mavlink_msg_memory_vect_pack_chan(system_id, component_id, chan, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); -} - -/** - * @brief Send a memory_vect message - * @param chan MAVLink channel to send the message - * - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#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, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#endif -} - -/** - * @brief Send a memory_vect message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_memory_vect_send_struct(mavlink_channel_t chan, const mavlink_memory_vect_t* memory_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_memory_vect_send(chan, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)memory_vect, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MEMORY_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_memory_vect_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#else - mavlink_memory_vect_t *packet = (mavlink_memory_vect_t *)msgbuf; - 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, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MEMORY_VECT UNPACKING - - -/** - * @brief Get field address from memory_vect message - * - * @return Starting address of the debug variables - */ -static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field ver from memory_vect message - * - * @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - */ -static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field type from memory_vect message - * - * @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - */ -static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field value from memory_vect message - * - * @return Memory contents at specified address - */ -static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value) -{ - return _MAV_RETURN_int8_t_array(msg, value, 32, 4); -} - -/** - * @brief Decode a memory_vect message into a struct - * - * @param msg The message to decode - * @param memory_vect C-struct to decode the message contents into - */ -static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - memory_vect->address = mavlink_msg_memory_vect_get_address(msg); - memory_vect->ver = mavlink_msg_memory_vect_get_ver(msg); - memory_vect->type = mavlink_msg_memory_vect_get_type(msg); - mavlink_msg_memory_vect_get_value(msg, memory_vect->value); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MEMORY_VECT_LEN? msg->len : MAVLINK_MSG_ID_MEMORY_VECT_LEN; - memset(memory_vect, 0, MAVLINK_MSG_ID_MEMORY_VECT_LEN); - memcpy(memory_vect, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_message_interval.h b/include/mavlink/v2.0/common/mavlink_msg_message_interval.h deleted file mode 100644 index 95b501f..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_message_interval.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE MESSAGE_INTERVAL PACKING - -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL 244 - -MAVPACKED( -typedef struct __mavlink_message_interval_t { - int32_t interval_us; /*< The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.*/ - uint16_t message_id; /*< The ID of the requested MAVLink message. v1.0 is limited to 254 messages.*/ -}) mavlink_message_interval_t; - -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN 6 -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN 6 -#define MAVLINK_MSG_ID_244_LEN 6 -#define MAVLINK_MSG_ID_244_MIN_LEN 6 - -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC 95 -#define MAVLINK_MSG_ID_244_CRC 95 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL { \ - 244, \ - "MESSAGE_INTERVAL", \ - 2, \ - { { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ - { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL { \ - "MESSAGE_INTERVAL", \ - 2, \ - { { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ - { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ - } \ -} -#endif - -/** - * @brief Pack a message_interval 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 message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_message_interval_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t message_id, int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#else - mavlink_message_interval_t packet; - packet.interval_us = interval_us; - packet.message_id = message_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -} - -/** - * @brief Pack a message_interval message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_message_interval_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t message_id,int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#else - mavlink_message_interval_t packet; - packet.interval_us = interval_us; - packet.message_id = message_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -} - -/** - * @brief Encode a message_interval struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param message_interval C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_message_interval_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval) -{ - return mavlink_msg_message_interval_pack(system_id, component_id, msg, message_interval->message_id, message_interval->interval_us); -} - -/** - * @brief Encode a message_interval struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param message_interval C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_message_interval_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval) -{ - return mavlink_msg_message_interval_pack_chan(system_id, component_id, chan, msg, message_interval->message_id, message_interval->interval_us); -} - -/** - * @brief Send a message_interval message - * @param chan MAVLink channel to send the message - * - * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_message_interval_send(mavlink_channel_t chan, uint16_t message_id, int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#else - mavlink_message_interval_t packet; - packet.interval_us = interval_us; - packet.message_id = message_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)&packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#endif -} - -/** - * @brief Send a message_interval message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_message_interval_send_struct(mavlink_channel_t chan, const mavlink_message_interval_t* message_interval) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_message_interval_send(chan, message_interval->message_id, message_interval->interval_us); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)message_interval, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_message_interval_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t message_id, int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#else - mavlink_message_interval_t *packet = (mavlink_message_interval_t *)msgbuf; - packet->interval_us = interval_us; - packet->message_id = message_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MESSAGE_INTERVAL UNPACKING - - -/** - * @brief Get field message_id from message_interval message - * - * @return The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - */ -static inline uint16_t mavlink_msg_message_interval_get_message_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field interval_us from message_interval message - * - * @return The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - */ -static inline int32_t mavlink_msg_message_interval_get_interval_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Decode a message_interval message into a struct - * - * @param msg The message to decode - * @param message_interval C-struct to decode the message contents into - */ -static inline void mavlink_msg_message_interval_decode(const mavlink_message_t* msg, mavlink_message_interval_t* message_interval) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - message_interval->interval_us = mavlink_msg_message_interval_get_interval_us(msg); - message_interval->message_id = mavlink_msg_message_interval_get_message_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN? msg->len : MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN; - memset(message_interval, 0, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); - memcpy(message_interval, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_ack.h b/include/mavlink/v2.0/common/mavlink_msg_mission_ack.h deleted file mode 100644 index a5c5e76..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_ack.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MISSION_ACK PACKING - -#define MAVLINK_MSG_ID_MISSION_ACK 47 - -MAVPACKED( -typedef struct __mavlink_mission_ack_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t type; /*< See MAV_MISSION_RESULT enum*/ - uint8_t mission_type; /*< Mission type, see MAV_MISSION_TYPE*/ -}) mavlink_mission_ack_t; - -#define MAVLINK_MSG_ID_MISSION_ACK_LEN 4 -#define MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN 3 -#define MAVLINK_MSG_ID_47_LEN 4 -#define MAVLINK_MSG_ID_47_MIN_LEN 3 - -#define MAVLINK_MSG_ID_MISSION_ACK_CRC 153 -#define MAVLINK_MSG_ID_47_CRC 153 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ - 47, \ - "MISSION_ACK", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_ack_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ - "MISSION_ACK", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_ack_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 3, mission_type); - - 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; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -} - -/** - * @brief Pack a mission_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t type,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 3, mission_type); - - 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; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -} - -/** - * @brief Encode a mission_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) -{ - return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type, mission_ack->mission_type); -} - -/** - * @brief Encode a mission_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) -{ - return mavlink_msg_mission_ack_pack_chan(system_id, component_id, chan, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type, mission_ack->mission_type); -} - -/** - * @brief Send a mission_ack message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum - * @param mission_type Mission type, see MAV_MISSION_TYPE - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 3, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#else - mavlink_mission_ack_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type = type; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#endif -} - -/** - * @brief Send a mission_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_ack_send_struct(mavlink_channel_t chan, const mavlink_mission_ack_t* mission_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_ack_send(chan, mission_ack->target_system, mission_ack->target_component, mission_ack->type, mission_ack->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)mission_ack, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, type); - _mav_put_uint8_t(buf, 3, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#else - mavlink_mission_ack_t *packet = (mavlink_mission_ack_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->type = type; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ACK UNPACKING - - -/** - * @brief Get field target_system from mission_ack message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_ack message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field type from mission_ack message - * - * @return See MAV_MISSION_RESULT enum - */ -static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field mission_type from mission_ack message - * - * @return Mission type, see MAV_MISSION_TYPE - */ -static inline uint8_t mavlink_msg_mission_ack_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Decode a mission_ack message into a struct - * - * @param msg The message to decode - * @param mission_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg, mavlink_mission_ack_t* mission_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_ack->target_system = mavlink_msg_mission_ack_get_target_system(msg); - mission_ack->target_component = mavlink_msg_mission_ack_get_target_component(msg); - mission_ack->type = mavlink_msg_mission_ack_get_type(msg); - mission_ack->mission_type = mavlink_msg_mission_ack_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ACK_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ACK_LEN; - memset(mission_ack, 0, MAVLINK_MSG_ID_MISSION_ACK_LEN); - memcpy(mission_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_clear_all.h b/include/mavlink/v2.0/common/mavlink_msg_mission_clear_all.h deleted file mode 100644 index 0039369..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_clear_all.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE MISSION_CLEAR_ALL PACKING - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45 - -MAVPACKED( -typedef struct __mavlink_mission_clear_all_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type, see MAV_MISSION_TYPE*/ -}) mavlink_mission_clear_all_t; - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 3 -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN 2 -#define MAVLINK_MSG_ID_45_LEN 3 -#define MAVLINK_MSG_ID_45_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC 232 -#define MAVLINK_MSG_ID_45_CRC 232 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ - 45, \ - "MISSION_CLEAR_ALL", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_clear_all_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ - "MISSION_CLEAR_ALL", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_clear_all_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_clear_all message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 2, mission_type); - - 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; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -} - -/** - * @brief Pack a mission_clear_all message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 2, mission_type); - - 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; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -} - -/** - * @brief Encode a mission_clear_all struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_clear_all C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) -{ - return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component, mission_clear_all->mission_type); -} - -/** - * @brief Encode a mission_clear_all struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_clear_all C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_clear_all_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) -{ - return mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, chan, msg, mission_clear_all->target_system, mission_clear_all->target_component, mission_clear_all->mission_type); -} - -/** - * @brief Send a mission_clear_all message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type, see MAV_MISSION_TYPE - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 2, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#else - mavlink_mission_clear_all_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#endif -} - -/** - * @brief Send a mission_clear_all message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_clear_all_send_struct(mavlink_channel_t chan, const mavlink_mission_clear_all_t* mission_clear_all) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_clear_all_send(chan, mission_clear_all->target_system, mission_clear_all->target_component, mission_clear_all->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)mission_clear_all, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_clear_all_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#else - mavlink_mission_clear_all_t *packet = (mavlink_mission_clear_all_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_CLEAR_ALL UNPACKING - - -/** - * @brief Get field target_system from mission_clear_all message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_clear_all message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field mission_type from mission_clear_all message - * - * @return Mission type, see MAV_MISSION_TYPE - */ -static inline uint8_t mavlink_msg_mission_clear_all_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a mission_clear_all message into a struct - * - * @param msg The message to decode - * @param mission_clear_all C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t* msg, mavlink_mission_clear_all_t* mission_clear_all) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - mission_clear_all->mission_type = mavlink_msg_mission_clear_all_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN? msg->len : MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN; - memset(mission_clear_all, 0, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); - memcpy(mission_clear_all, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_count.h b/include/mavlink/v2.0/common/mavlink_msg_mission_count.h deleted file mode 100644 index 19d5556..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_count.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MISSION_COUNT PACKING - -#define MAVLINK_MSG_ID_MISSION_COUNT 44 - -MAVPACKED( -typedef struct __mavlink_mission_count_t { - uint16_t count; /*< Number of mission items in the sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type, see MAV_MISSION_TYPE*/ -}) mavlink_mission_count_t; - -#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 5 -#define MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN 4 -#define MAVLINK_MSG_ID_44_LEN 5 -#define MAVLINK_MSG_ID_44_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_COUNT_CRC 221 -#define MAVLINK_MSG_ID_44_CRC 221 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ - 44, \ - "MISSION_COUNT", \ - 4, \ - { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_count_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ - "MISSION_COUNT", \ - 4, \ - { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_count_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_count message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 4, mission_type); - - 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; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -} - -/** - * @brief Pack a mission_count message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t count,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 4, mission_type); - - 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; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -} - -/** - * @brief Encode a mission_count struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_count C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) -{ - return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type); -} - -/** - * @brief Encode a mission_count struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_count C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_count_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) -{ - return mavlink_msg_mission_count_pack_chan(system_id, component_id, chan, msg, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type); -} - -/** - * @brief Send a mission_count message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - * @param mission_type Mission type, see MAV_MISSION_TYPE - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#else - mavlink_mission_count_t packet; - packet.count = count; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#endif -} - -/** - * @brief Send a mission_count message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_count_send_struct(mavlink_channel_t chan, const mavlink_mission_count_t* mission_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_count_send(chan, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)mission_count, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_COUNT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, count); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#else - mavlink_mission_count_t *packet = (mavlink_mission_count_t *)msgbuf; - packet->count = count; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_COUNT UNPACKING - - -/** - * @brief Get field target_system from mission_count message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_count message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field count from mission_count message - * - * @return Number of mission items in the sequence - */ -static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field mission_type from mission_count message - * - * @return Mission type, see MAV_MISSION_TYPE - */ -static inline uint8_t mavlink_msg_mission_count_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Decode a mission_count message into a struct - * - * @param msg The message to decode - * @param mission_count C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_count->count = mavlink_msg_mission_count_get_count(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); - mission_count->mission_type = mavlink_msg_mission_count_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_COUNT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_COUNT_LEN; - memset(mission_count, 0, MAVLINK_MSG_ID_MISSION_COUNT_LEN); - memcpy(mission_count, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_current.h b/include/mavlink/v2.0/common/mavlink_msg_mission_current.h deleted file mode 100644 index 802632d..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_current.h +++ /dev/null @@ -1,213 +0,0 @@ -#pragma once -// MESSAGE MISSION_CURRENT PACKING - -#define MAVLINK_MSG_ID_MISSION_CURRENT 42 - -MAVPACKED( -typedef struct __mavlink_mission_current_t { - uint16_t seq; /*< Sequence*/ -}) mavlink_mission_current_t; - -#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2 -#define MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN 2 -#define MAVLINK_MSG_ID_42_LEN 2 -#define MAVLINK_MSG_ID_42_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_CURRENT_CRC 28 -#define MAVLINK_MSG_ID_42_CRC 28 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ - 42, \ - "MISSION_CURRENT", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ - "MISSION_CURRENT", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_current 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 seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - 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, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -} - -/** - * @brief Pack a mission_current message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - 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, 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, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -} - -/** - * @brief Encode a mission_current struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) -{ - return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq); -} - -/** - * @brief Encode a mission_current struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) -{ - return mavlink_msg_mission_current_pack_chan(system_id, component_id, chan, msg, mission_current->seq); -} - -/** - * @brief Send a mission_current message - * @param chan MAVLink channel to send the message - * - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - mavlink_mission_current_t packet; - packet.seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#endif -} - -/** - * @brief Send a mission_current message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_current_send_struct(mavlink_channel_t chan, const mavlink_mission_current_t* mission_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_current_send(chan, mission_current->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)mission_current, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - mavlink_mission_current_t *packet = (mavlink_mission_current_t *)msgbuf; - packet->seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_CURRENT UNPACKING - - -/** - * @brief Get field seq from mission_current message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_current message into a struct - * - * @param msg The message to decode - * @param mission_current C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_current->seq = mavlink_msg_mission_current_get_seq(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_CURRENT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_CURRENT_LEN; - memset(mission_current, 0, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); - memcpy(mission_current, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_item.h b/include/mavlink/v2.0/common/mavlink_msg_mission_item.h deleted file mode 100644 index a044e65..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_item.h +++ /dev/null @@ -1,563 +0,0 @@ -#pragma once -// MESSAGE MISSION_ITEM PACKING - -#define MAVLINK_MSG_ID_MISSION_ITEM 39 - -MAVPACKED( -typedef struct __mavlink_mission_item_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - float x; /*< PARAM5 / local: x position, global: latitude*/ - float y; /*< PARAM6 / y position: global: longitude*/ - float z; /*< PARAM7 / z position: global: altitude (relative or absolute, depending on frame.*/ - uint16_t seq; /*< Sequence*/ - uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/ - uint8_t current; /*< false:0, true:1*/ - uint8_t autocontinue; /*< autocontinue to next wp*/ - uint8_t mission_type; /*< Mission type, see MAV_MISSION_TYPE*/ -}) mavlink_mission_item_t; - -#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 38 -#define MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN 37 -#define MAVLINK_MSG_ID_39_LEN 38 -#define MAVLINK_MSG_ID_39_MIN_LEN 37 - -#define MAVLINK_MSG_ID_MISSION_ITEM_CRC 254 -#define MAVLINK_MSG_ID_39_CRC 254 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ - 39, \ - "MISSION_ITEM", \ - 15, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ - "MISSION_ITEM", \ - 15, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_item message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -} - -/** - * @brief Pack a mission_item message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -} - -/** - * @brief Encode a mission_item struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_item C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) -{ - return mavlink_msg_mission_item_pack(system_id, component_id, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z, mission_item->mission_type); -} - -/** - * @brief Encode a mission_item struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_item C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) -{ - return mavlink_msg_mission_item_pack_chan(system_id, component_id, chan, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z, mission_item->mission_type); -} - -/** - * @brief Send a mission_item message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - * @param mission_type Mission type, see MAV_MISSION_TYPE - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#endif -} - -/** - * @brief Send a mission_item message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_item_send_struct(mavlink_channel_t chan, const mavlink_mission_item_t* mission_item) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_item_send(chan, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z, mission_item->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)mission_item, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ITEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_item_send_buf(mavlink_message_t *msgbuf, 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, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - mavlink_mission_item_t *packet = (mavlink_mission_item_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->x = x; - packet->y = y; - packet->z = z; - packet->seq = seq; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - packet->current = current; - packet->autocontinue = autocontinue; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ITEM UNPACKING - - -/** - * @brief Get field target_system from mission_item message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field target_component from mission_item message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field seq from mission_item message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field frame from mission_item message - * - * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - */ -static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field command from mission_item message - * - * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - */ -static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field current from mission_item message - * - * @return false:0, true:1 - */ -static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field autocontinue from mission_item message - * - * @return autocontinue to next wp - */ -static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field param1 from mission_item message - * - * @return PARAM1, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from mission_item message - * - * @return PARAM2, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from mission_item message - * - * @return PARAM3, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from mission_item message - * - * @return PARAM4, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field x from mission_item message - * - * @return PARAM5 / local: x position, global: latitude - */ -static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field y from mission_item message - * - * @return PARAM6 / y position: global: longitude - */ -static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field z from mission_item message - * - * @return PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - */ -static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field mission_type from mission_item message - * - * @return Mission type, see MAV_MISSION_TYPE - */ -static inline uint8_t mavlink_msg_mission_item_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 37); -} - -/** - * @brief Decode a mission_item message into a struct - * - * @param msg The message to decode - * @param mission_item C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* msg, mavlink_mission_item_t* mission_item) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_item->param1 = mavlink_msg_mission_item_get_param1(msg); - mission_item->param2 = mavlink_msg_mission_item_get_param2(msg); - mission_item->param3 = mavlink_msg_mission_item_get_param3(msg); - mission_item->param4 = mavlink_msg_mission_item_get_param4(msg); - mission_item->x = mavlink_msg_mission_item_get_x(msg); - mission_item->y = mavlink_msg_mission_item_get_y(msg); - mission_item->z = mavlink_msg_mission_item_get_z(msg); - mission_item->seq = mavlink_msg_mission_item_get_seq(msg); - mission_item->command = mavlink_msg_mission_item_get_command(msg); - mission_item->target_system = mavlink_msg_mission_item_get_target_system(msg); - mission_item->target_component = mavlink_msg_mission_item_get_target_component(msg); - mission_item->frame = mavlink_msg_mission_item_get_frame(msg); - mission_item->current = mavlink_msg_mission_item_get_current(msg); - mission_item->autocontinue = mavlink_msg_mission_item_get_autocontinue(msg); - mission_item->mission_type = mavlink_msg_mission_item_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_LEN; - memset(mission_item, 0, MAVLINK_MSG_ID_MISSION_ITEM_LEN); - memcpy(mission_item, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_item_int.h b/include/mavlink/v2.0/common/mavlink_msg_mission_item_int.h deleted file mode 100644 index acfc8ae..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_item_int.h +++ /dev/null @@ -1,563 +0,0 @@ -#pragma once -// MESSAGE MISSION_ITEM_INT PACKING - -#define MAVLINK_MSG_ID_MISSION_ITEM_INT 73 - -MAVPACKED( -typedef struct __mavlink_mission_item_int_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ - int32_t y; /*< PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7*/ - float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ - uint16_t seq; /*< Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).*/ - uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/ - uint8_t current; /*< false:0, true:1*/ - uint8_t autocontinue; /*< autocontinue to next wp*/ - uint8_t mission_type; /*< Mission type, see MAV_MISSION_TYPE*/ -}) mavlink_mission_item_int_t; - -#define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 38 -#define MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN 37 -#define MAVLINK_MSG_ID_73_LEN 38 -#define MAVLINK_MSG_ID_73_MIN_LEN 37 - -#define MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC 38 -#define MAVLINK_MSG_ID_73_CRC 38 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \ - 73, \ - "MISSION_ITEM_INT", \ - 15, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_int_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \ - "MISSION_ITEM_INT", \ - 15, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_int_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_item_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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, int32_t x, int32_t y, float z, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#else - mavlink_mission_item_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -} - -/** - * @brief Pack a mission_item_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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,int32_t x,int32_t y,float z,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#else - mavlink_mission_item_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -} - -/** - * @brief Encode a mission_item_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_item_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int) -{ - return mavlink_msg_mission_item_int_pack(system_id, component_id, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z, mission_item_int->mission_type); -} - -/** - * @brief Encode a mission_item_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_item_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int) -{ - return mavlink_msg_mission_item_int_pack_chan(system_id, component_id, chan, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z, mission_item_int->mission_type); -} - -/** - * @brief Send a mission_item_int message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @param mission_type Mission type, see MAV_MISSION_TYPE - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_item_int_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, int32_t x, int32_t y, float z, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#else - mavlink_mission_item_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#endif -} - -/** - * @brief Send a mission_item_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_item_int_send_struct(mavlink_channel_t chan, const mavlink_mission_item_int_t* mission_item_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_item_int_send(chan, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z, mission_item_int->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)mission_item_int, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgbuf, 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, int32_t x, int32_t y, float z, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#else - mavlink_mission_item_int_t *packet = (mavlink_mission_item_int_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->x = x; - packet->y = y; - packet->z = z; - packet->seq = seq; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - packet->current = current; - packet->autocontinue = autocontinue; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ITEM_INT UNPACKING - - -/** - * @brief Get field target_system from mission_item_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_item_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field target_component from mission_item_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_item_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field seq from mission_item_int message - * - * @return Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - */ -static inline uint16_t mavlink_msg_mission_item_int_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field frame from mission_item_int message - * - * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - */ -static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field command from mission_item_int message - * - * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - */ -static inline uint16_t mavlink_msg_mission_item_int_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field current from mission_item_int message - * - * @return false:0, true:1 - */ -static inline uint8_t mavlink_msg_mission_item_int_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field autocontinue from mission_item_int message - * - * @return autocontinue to next wp - */ -static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field param1 from mission_item_int message - * - * @return PARAM1, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from mission_item_int message - * - * @return PARAM2, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from mission_item_int message - * - * @return PARAM3, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from mission_item_int message - * - * @return PARAM4, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field x from mission_item_int message - * - * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - */ -static inline int32_t mavlink_msg_mission_item_int_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field y from mission_item_int message - * - * @return PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - */ -static inline int32_t mavlink_msg_mission_item_int_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field z from mission_item_int message - * - * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - */ -static inline float mavlink_msg_mission_item_int_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field mission_type from mission_item_int message - * - * @return Mission type, see MAV_MISSION_TYPE - */ -static inline uint8_t mavlink_msg_mission_item_int_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 37); -} - -/** - * @brief Decode a mission_item_int message into a struct - * - * @param msg The message to decode - * @param mission_item_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_item_int_decode(const mavlink_message_t* msg, mavlink_mission_item_int_t* mission_item_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_item_int->param1 = mavlink_msg_mission_item_int_get_param1(msg); - mission_item_int->param2 = mavlink_msg_mission_item_int_get_param2(msg); - mission_item_int->param3 = mavlink_msg_mission_item_int_get_param3(msg); - mission_item_int->param4 = mavlink_msg_mission_item_int_get_param4(msg); - mission_item_int->x = mavlink_msg_mission_item_int_get_x(msg); - mission_item_int->y = mavlink_msg_mission_item_int_get_y(msg); - mission_item_int->z = mavlink_msg_mission_item_int_get_z(msg); - mission_item_int->seq = mavlink_msg_mission_item_int_get_seq(msg); - mission_item_int->command = mavlink_msg_mission_item_int_get_command(msg); - mission_item_int->target_system = mavlink_msg_mission_item_int_get_target_system(msg); - mission_item_int->target_component = mavlink_msg_mission_item_int_get_target_component(msg); - mission_item_int->frame = mavlink_msg_mission_item_int_get_frame(msg); - mission_item_int->current = mavlink_msg_mission_item_int_get_current(msg); - mission_item_int->autocontinue = mavlink_msg_mission_item_int_get_autocontinue(msg); - mission_item_int->mission_type = mavlink_msg_mission_item_int_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN; - memset(mission_item_int, 0, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); - memcpy(mission_item_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_item_reached.h b/include/mavlink/v2.0/common/mavlink_msg_mission_item_reached.h deleted file mode 100644 index 1ad0e29..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_item_reached.h +++ /dev/null @@ -1,213 +0,0 @@ -#pragma once -// MESSAGE MISSION_ITEM_REACHED PACKING - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46 - -MAVPACKED( -typedef struct __mavlink_mission_item_reached_t { - uint16_t seq; /*< Sequence*/ -}) mavlink_mission_item_reached_t; - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN 2 -#define MAVLINK_MSG_ID_46_LEN 2 -#define MAVLINK_MSG_ID_46_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC 11 -#define MAVLINK_MSG_ID_46_CRC 11 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ - 46, \ - "MISSION_ITEM_REACHED", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ - "MISSION_ITEM_REACHED", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_item_reached 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 seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - 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, 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, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -} - -/** - * @brief Pack a mission_item_reached message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - 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, 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, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -} - -/** - * @brief Encode a mission_item_reached struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_item_reached C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) -{ - return mavlink_msg_mission_item_reached_pack(system_id, component_id, msg, mission_item_reached->seq); -} - -/** - * @brief Encode a mission_item_reached struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_item_reached C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_reached_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) -{ - return mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, chan, msg, mission_item_reached->seq); -} - -/** - * @brief Send a mission_item_reached message - * @param chan MAVLink channel to send the message - * - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#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, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#endif -} - -/** - * @brief Send a mission_item_reached message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_item_reached_send_struct(mavlink_channel_t chan, const mavlink_mission_item_reached_t* mission_item_reached) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_item_reached_send(chan, mission_item_reached->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)mission_item_reached, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_item_reached_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#else - mavlink_mission_item_reached_t *packet = (mavlink_mission_item_reached_t *)msgbuf; - packet->seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ITEM_REACHED UNPACKING - - -/** - * @brief Get field seq from mission_item_reached message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_item_reached_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_item_reached message into a struct - * - * @param msg The message to decode - * @param mission_item_reached C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_item_reached_decode(const mavlink_message_t* msg, mavlink_mission_item_reached_t* mission_item_reached) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_item_reached->seq = mavlink_msg_mission_item_reached_get_seq(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN; - memset(mission_item_reached, 0, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); - memcpy(mission_item_reached, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_request.h b/include/mavlink/v2.0/common/mavlink_msg_mission_request.h deleted file mode 100644 index 3307fb2..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_request.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST 40 - -MAVPACKED( -typedef struct __mavlink_mission_request_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type, see MAV_MISSION_TYPE*/ -}) mavlink_mission_request_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 5 -#define MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN 4 -#define MAVLINK_MSG_ID_40_LEN 5 -#define MAVLINK_MSG_ID_40_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230 -#define MAVLINK_MSG_ID_40_CRC 230 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ - 40, \ - "MISSION_REQUEST", \ - 4, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ - "MISSION_REQUEST", \ - 4, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 4, mission_type); - - 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; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -} - -/** - * @brief Pack a mission_request message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 4, mission_type); - - 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; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -} - -/** - * @brief Encode a mission_request struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) -{ - return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type); -} - -/** - * @brief Encode a mission_request struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) -{ - return mavlink_msg_mission_request_pack_chan(system_id, component_id, chan, msg, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type); -} - -/** - * @brief Send a mission_request message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type, see MAV_MISSION_TYPE - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#else - mavlink_mission_request_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#endif -} - -/** - * @brief Send a mission_request message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_send_struct(mavlink_channel_t chan, const mavlink_mission_request_t* mission_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_send(chan, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)mission_request, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#else - mavlink_mission_request_t *packet = (mavlink_mission_request_t *)msgbuf; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST UNPACKING - - -/** - * @brief Get field target_system from mission_request message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_request message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field seq from mission_request message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field mission_type from mission_request message - * - * @return Mission type, see MAV_MISSION_TYPE - */ -static inline uint8_t mavlink_msg_mission_request_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Decode a mission_request message into a struct - * - * @param msg The message to decode - * @param mission_request C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_request->seq = mavlink_msg_mission_request_get_seq(msg); - mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg); - mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg); - mission_request->mission_type = mavlink_msg_mission_request_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_LEN; - memset(mission_request, 0, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); - memcpy(mission_request, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_request_int.h b/include/mavlink/v2.0/common/mavlink_msg_mission_request_int.h deleted file mode 100644 index bb0773f..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_request_int.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST_INT PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT 51 - -MAVPACKED( -typedef struct __mavlink_mission_request_int_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type, see MAV_MISSION_TYPE*/ -}) mavlink_mission_request_int_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN 5 -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN 4 -#define MAVLINK_MSG_ID_51_LEN 5 -#define MAVLINK_MSG_ID_51_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC 196 -#define MAVLINK_MSG_ID_51_CRC 196 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \ - 51, \ - "MISSION_REQUEST_INT", \ - 4, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_int_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \ - "MISSION_REQUEST_INT", \ - 4, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_int_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_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_put_uint8_t(buf, 4, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#else - mavlink_mission_request_int_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -} - -/** - * @brief Pack a mission_request_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_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_put_uint8_t(buf, 4, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#else - mavlink_mission_request_int_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -} - -/** - * @brief Encode a mission_request_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int) -{ - return mavlink_msg_mission_request_int_pack(system_id, component_id, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type); -} - -/** - * @brief Encode a mission_request_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int) -{ - return mavlink_msg_mission_request_int_pack_chan(system_id, component_id, chan, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type); -} - -/** - * @brief Send a mission_request_int message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type, see MAV_MISSION_TYPE - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_request_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_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_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#else - mavlink_mission_request_int_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#endif -} - -/** - * @brief Send a mission_request_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_int_send_struct(mavlink_channel_t chan, const mavlink_mission_request_int_t* mission_request_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_int_send(chan, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)mission_request_int, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#else - mavlink_mission_request_int_t *packet = (mavlink_mission_request_int_t *)msgbuf; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST_INT UNPACKING - - -/** - * @brief Get field target_system from mission_request_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_request_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field seq from mission_request_int message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_request_int_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field mission_type from mission_request_int message - * - * @return Mission type, see MAV_MISSION_TYPE - */ -static inline uint8_t mavlink_msg_mission_request_int_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Decode a mission_request_int message into a struct - * - * @param msg The message to decode - * @param mission_request_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_int_decode(const mavlink_message_t* msg, mavlink_mission_request_int_t* mission_request_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_request_int->seq = mavlink_msg_mission_request_int_get_seq(msg); - mission_request_int->target_system = mavlink_msg_mission_request_int_get_target_system(msg); - mission_request_int->target_component = mavlink_msg_mission_request_int_get_target_component(msg); - mission_request_int->mission_type = mavlink_msg_mission_request_int_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN; - memset(mission_request_int, 0, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); - memcpy(mission_request_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_request_list.h b/include/mavlink/v2.0/common/mavlink_msg_mission_request_list.h deleted file mode 100644 index 9022522..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_request_list.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43 - -MAVPACKED( -typedef struct __mavlink_mission_request_list_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type, see MAV_MISSION_TYPE*/ -}) mavlink_mission_request_list_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 3 -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN 2 -#define MAVLINK_MSG_ID_43_LEN 3 -#define MAVLINK_MSG_ID_43_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC 132 -#define MAVLINK_MSG_ID_43_CRC 132 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ - 43, \ - "MISSION_REQUEST_LIST", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_list_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ - "MISSION_REQUEST_LIST", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_list_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 2, mission_type); - - 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; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -} - -/** - * @brief Pack a mission_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 2, mission_type); - - 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; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -} - -/** - * @brief Encode a mission_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) -{ - return mavlink_msg_mission_request_list_pack(system_id, component_id, msg, mission_request_list->target_system, mission_request_list->target_component, mission_request_list->mission_type); -} - -/** - * @brief Encode a mission_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) -{ - return mavlink_msg_mission_request_list_pack_chan(system_id, component_id, chan, msg, mission_request_list->target_system, mission_request_list->target_component, mission_request_list->mission_type); -} - -/** - * @brief Send a mission_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type, see MAV_MISSION_TYPE - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 2, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#else - mavlink_mission_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#endif -} - -/** - * @brief Send a mission_request_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_list_send_struct(mavlink_channel_t chan, const mavlink_mission_request_list_t* mission_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_list_send(chan, mission_request_list->target_system, mission_request_list->target_component, mission_request_list->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)mission_request_list, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#else - mavlink_mission_request_list_t *packet = (mavlink_mission_request_list_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field mission_type from mission_request_list message - * - * @return Mission type, see MAV_MISSION_TYPE - */ -static inline uint8_t mavlink_msg_mission_request_list_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a mission_request_list message into a struct - * - * @param msg The message to decode - * @param mission_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_list_decode(const mavlink_message_t* msg, mavlink_mission_request_list_t* mission_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - mission_request_list->mission_type = mavlink_msg_mission_request_list_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN; - memset(mission_request_list, 0, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); - memcpy(mission_request_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_request_partial_list.h b/include/mavlink/v2.0/common/mavlink_msg_mission_request_partial_list.h deleted file mode 100644 index bbd4b82..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_request_partial_list.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST_PARTIAL_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37 - -MAVPACKED( -typedef struct __mavlink_mission_request_partial_list_t { - int16_t start_index; /*< Start index, 0 by default*/ - int16_t end_index; /*< End index, -1 by default (-1: send list to end). Else a valid index of the list*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type, see MAV_MISSION_TYPE*/ -}) mavlink_mission_request_partial_list_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 7 -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN 6 -#define MAVLINK_MSG_ID_37_LEN 7 -#define MAVLINK_MSG_ID_37_MIN_LEN 6 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212 -#define MAVLINK_MSG_ID_37_CRC 212 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ - 37, \ - "MISSION_REQUEST_PARTIAL_LIST", \ - 5, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_request_partial_list_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ - "MISSION_REQUEST_PARTIAL_LIST", \ - 5, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_request_partial_list_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request_partial_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 6, mission_type); - - 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; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -} - -/** - * @brief Pack a mission_request_partial_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 6, mission_type); - - 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; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -} - -/** - * @brief Encode a mission_request_partial_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ - return mavlink_msg_mission_request_partial_list_pack(system_id, component_id, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index, mission_request_partial_list->mission_type); -} - -/** - * @brief Encode a mission_request_partial_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ - return mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, chan, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index, mission_request_partial_list->mission_type); -} - -/** - * @brief Send a mission_request_partial_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - * @param mission_type Mission type, see MAV_MISSION_TYPE - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 6, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - mavlink_mission_request_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#endif -} - -/** - * @brief Send a mission_request_partial_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_partial_list_send_struct(mavlink_channel_t chan, const mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_partial_list_send(chan, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index, mission_request_partial_list->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)mission_request_partial_list, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - mavlink_mission_request_partial_list_t *packet = (mavlink_mission_request_partial_list_t *)msgbuf; - packet->start_index = start_index; - packet->end_index = end_index; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST_PARTIAL_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_request_partial_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from mission_request_partial_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start_index from mission_request_partial_list message - * - * @return Start index, 0 by default - */ -static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field end_index from mission_request_partial_list message - * - * @return End index, -1 by default (-1: send list to end). Else a valid index of the list - */ -static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Get field mission_type from mission_request_partial_list message - * - * @return Mission type, see MAV_MISSION_TYPE - */ -static inline uint8_t mavlink_msg_mission_request_partial_list_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Decode a mission_request_partial_list message into a struct - * - * @param msg The message to decode - * @param mission_request_partial_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_request_partial_list->start_index = mavlink_msg_mission_request_partial_list_get_start_index(msg); - mission_request_partial_list->end_index = mavlink_msg_mission_request_partial_list_get_end_index(msg); - 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); - mission_request_partial_list->mission_type = mavlink_msg_mission_request_partial_list_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN; - memset(mission_request_partial_list, 0, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); - memcpy(mission_request_partial_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_set_current.h b/include/mavlink/v2.0/common/mavlink_msg_mission_set_current.h deleted file mode 100644 index 50942fc..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_set_current.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE MISSION_SET_CURRENT PACKING - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT 41 - -MAVPACKED( -typedef struct __mavlink_mission_set_current_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_mission_set_current_t; - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN 4 -#define MAVLINK_MSG_ID_41_LEN 4 -#define MAVLINK_MSG_ID_41_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC 28 -#define MAVLINK_MSG_ID_41_CRC 28 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ - 41, \ - "MISSION_SET_CURRENT", \ - 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ - "MISSION_SET_CURRENT", \ - 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_set_current message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -} - -/** - * @brief Pack a mission_set_current message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_set_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -} - -/** - * @brief Encode a mission_set_current struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_set_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) -{ - return mavlink_msg_mission_set_current_pack(system_id, component_id, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); -} - -/** - * @brief Encode a mission_set_current struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_set_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_set_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) -{ - return mavlink_msg_mission_set_current_pack_chan(system_id, component_id, chan, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); -} - -/** - * @brief Send a mission_set_current message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#endif -} - -/** - * @brief Send a mission_set_current message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_set_current_send_struct(mavlink_channel_t chan, const mavlink_mission_set_current_t* mission_set_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_set_current_send(chan, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)mission_set_current, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_set_current_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#else - mavlink_mission_set_current_t *packet = (mavlink_mission_set_current_t *)msgbuf; - 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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_SET_CURRENT UNPACKING - - -/** - * @brief Get field target_system from mission_set_current message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_set_current_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_set_current message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_set_current_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field seq from mission_set_current message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_set_current_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_set_current message into a struct - * - * @param msg The message to decode - * @param mission_set_current C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_set_current_decode(const mavlink_message_t* msg, mavlink_mission_set_current_t* mission_set_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_set_current->seq = mavlink_msg_mission_set_current_get_seq(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN; - memset(mission_set_current, 0, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); - memcpy(mission_set_current, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mission_write_partial_list.h b/include/mavlink/v2.0/common/mavlink_msg_mission_write_partial_list.h deleted file mode 100644 index 68df2d5..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mission_write_partial_list.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE MISSION_WRITE_PARTIAL_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38 - -MAVPACKED( -typedef struct __mavlink_mission_write_partial_list_t { - int16_t start_index; /*< Start index, 0 by default and smaller / equal to the largest index of the current onboard list.*/ - int16_t end_index; /*< End index, equal or greater than start index.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type, see MAV_MISSION_TYPE*/ -}) mavlink_mission_write_partial_list_t; - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 7 -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN 6 -#define MAVLINK_MSG_ID_38_LEN 7 -#define MAVLINK_MSG_ID_38_MIN_LEN 6 - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9 -#define MAVLINK_MSG_ID_38_CRC 9 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ - 38, \ - "MISSION_WRITE_PARTIAL_LIST", \ - 5, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_write_partial_list_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ - "MISSION_WRITE_PARTIAL_LIST", \ - 5, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_write_partial_list_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_write_partial_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 6, mission_type); - - 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; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -} - -/** - * @brief Pack a mission_write_partial_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - * @param mission_type Mission type, see MAV_MISSION_TYPE - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 6, mission_type); - - 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; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - 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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -} - -/** - * @brief Encode a mission_write_partial_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_write_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ - return mavlink_msg_mission_write_partial_list_pack(system_id, component_id, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index, mission_write_partial_list->mission_type); -} - -/** - * @brief Encode a mission_write_partial_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_write_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ - return mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, chan, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index, mission_write_partial_list->mission_type); -} - -/** - * @brief Send a mission_write_partial_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - * @param mission_type Mission type, see MAV_MISSION_TYPE - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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_put_uint8_t(buf, 6, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - mavlink_mission_write_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#endif -} - -/** - * @brief Send a mission_write_partial_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_write_partial_list_send_struct(mavlink_channel_t chan, const mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_write_partial_list_send(chan, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index, mission_write_partial_list->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)mission_write_partial_list, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_write_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - mavlink_mission_write_partial_list_t *packet = (mavlink_mission_write_partial_list_t *)msgbuf; - packet->start_index = start_index; - packet->end_index = end_index; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_WRITE_PARTIAL_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_write_partial_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from mission_write_partial_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start_index from mission_write_partial_list message - * - * @return Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - */ -static inline int16_t mavlink_msg_mission_write_partial_list_get_start_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field end_index from mission_write_partial_list message - * - * @return End index, equal or greater than start index. - */ -static inline int16_t mavlink_msg_mission_write_partial_list_get_end_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Get field mission_type from mission_write_partial_list message - * - * @return Mission type, see MAV_MISSION_TYPE - */ -static inline uint8_t mavlink_msg_mission_write_partial_list_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Decode a mission_write_partial_list message into a struct - * - * @param msg The message to decode - * @param mission_write_partial_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_write_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_write_partial_list->start_index = mavlink_msg_mission_write_partial_list_get_start_index(msg); - mission_write_partial_list->end_index = mavlink_msg_mission_write_partial_list_get_end_index(msg); - 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); - mission_write_partial_list->mission_type = mavlink_msg_mission_write_partial_list_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN; - memset(mission_write_partial_list, 0, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); - memcpy(mission_write_partial_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_mount_orientation.h b/include/mavlink/v2.0/common/mavlink_msg_mount_orientation.h deleted file mode 100644 index 467a455..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_mount_orientation.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MOUNT_ORIENTATION PACKING - -#define MAVLINK_MSG_ID_MOUNT_ORIENTATION 265 - -MAVPACKED( -typedef struct __mavlink_mount_orientation_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float roll; /*< Roll in degrees*/ - float pitch; /*< Pitch in degrees*/ - float yaw; /*< Yaw in degrees*/ -}) mavlink_mount_orientation_t; - -#define MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN 16 -#define MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN 16 -#define MAVLINK_MSG_ID_265_LEN 16 -#define MAVLINK_MSG_ID_265_MIN_LEN 16 - -#define MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC 26 -#define MAVLINK_MSG_ID_265_CRC 26 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION { \ - 265, \ - "MOUNT_ORIENTATION", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_mount_orientation_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mount_orientation_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mount_orientation_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mount_orientation_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION { \ - "MOUNT_ORIENTATION", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_mount_orientation_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mount_orientation_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mount_orientation_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mount_orientation_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a mount_orientation 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_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll in degrees - * @param pitch Pitch in degrees - * @param yaw Yaw in degrees - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mount_orientation_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_ORIENTATION_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); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN); -#else - mavlink_mount_orientation_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MOUNT_ORIENTATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -} - -/** - * @brief Pack a mount_orientation message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll in degrees - * @param pitch Pitch in degrees - * @param yaw Yaw in degrees - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mount_orientation_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float roll,float pitch,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_ORIENTATION_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); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN); -#else - mavlink_mount_orientation_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MOUNT_ORIENTATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -} - -/** - * @brief Encode a mount_orientation struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mount_orientation C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mount_orientation_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_orientation_t* mount_orientation) -{ - return mavlink_msg_mount_orientation_pack(system_id, component_id, msg, mount_orientation->time_boot_ms, mount_orientation->roll, mount_orientation->pitch, mount_orientation->yaw); -} - -/** - * @brief Encode a mount_orientation struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mount_orientation C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mount_orientation_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_orientation_t* mount_orientation) -{ - return mavlink_msg_mount_orientation_pack_chan(system_id, component_id, chan, msg, mount_orientation->time_boot_ms, mount_orientation->roll, mount_orientation->pitch, mount_orientation->yaw); -} - -/** - * @brief Send a mount_orientation message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll in degrees - * @param pitch Pitch in degrees - * @param yaw Yaw in degrees - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mount_orientation_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_ORIENTATION_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_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -#else - mavlink_mount_orientation_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -#endif -} - -/** - * @brief Send a mount_orientation message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mount_orientation_send_struct(mavlink_channel_t chan, const mavlink_mount_orientation_t* mount_orientation) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mount_orientation_send(chan, mount_orientation->time_boot_ms, mount_orientation->roll, mount_orientation->pitch, mount_orientation->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, (const char *)mount_orientation, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mount_orientation_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -#else - mavlink_mount_orientation_t *packet = (mavlink_mount_orientation_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, (const char *)packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MOUNT_ORIENTATION UNPACKING - - -/** - * @brief Get field time_boot_ms from mount_orientation message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_mount_orientation_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll from mount_orientation message - * - * @return Roll in degrees - */ -static inline float mavlink_msg_mount_orientation_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch from mount_orientation message - * - * @return Pitch in degrees - */ -static inline float mavlink_msg_mount_orientation_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from mount_orientation message - * - * @return Yaw in degrees - */ -static inline float mavlink_msg_mount_orientation_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a mount_orientation message into a struct - * - * @param msg The message to decode - * @param mount_orientation C-struct to decode the message contents into - */ -static inline void mavlink_msg_mount_orientation_decode(const mavlink_message_t* msg, mavlink_mount_orientation_t* mount_orientation) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mount_orientation->time_boot_ms = mavlink_msg_mount_orientation_get_time_boot_ms(msg); - mount_orientation->roll = mavlink_msg_mount_orientation_get_roll(msg); - mount_orientation->pitch = mavlink_msg_mount_orientation_get_pitch(msg); - mount_orientation->yaw = mavlink_msg_mount_orientation_get_yaw(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN? msg->len : MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN; - memset(mount_orientation, 0, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN); - memcpy(mount_orientation, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_named_value_float.h b/include/mavlink/v2.0/common/mavlink_msg_named_value_float.h deleted file mode 100644 index 99cf094..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_named_value_float.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE NAMED_VALUE_FLOAT PACKING - -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 - -MAVPACKED( -typedef struct __mavlink_named_value_float_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float value; /*< Floating point value*/ - char name[10]; /*< Name of the debug variable*/ -}) mavlink_named_value_float_t; - -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN 18 -#define MAVLINK_MSG_ID_251_LEN 18 -#define MAVLINK_MSG_ID_251_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ - 251, \ - "NAMED_VALUE_FLOAT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ - "NAMED_VALUE_FLOAT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ - } \ -} -#endif - -/** - * @brief Pack a named_value_float 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_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, const char *name, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -} - -/** - * @brief Pack a named_value_float message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,const char *name,float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -} - -/** - * @brief Encode a named_value_float struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param named_value_float C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) -{ - return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); -} - -/** - * @brief Encode a named_value_float struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param named_value_float C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_float_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) -{ - return mavlink_msg_named_value_float_pack_chan(system_id, component_id, chan, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); -} - -/** - * @brief Send a named_value_float message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#endif -} - -/** - * @brief Send a named_value_float message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_named_value_float_send_struct(mavlink_channel_t chan, const mavlink_named_value_float_t* named_value_float) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_named_value_float_send(chan, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)named_value_float, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_named_value_float_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#else - mavlink_named_value_float_t *packet = (mavlink_named_value_float_t *)msgbuf; - 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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE NAMED_VALUE_FLOAT UNPACKING - - -/** - * @brief Get field time_boot_ms from named_value_float message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field name from named_value_float message - * - * @return Name of the debug variable - */ -static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 8); -} - -/** - * @brief Get field value from named_value_float message - * - * @return Floating point value - */ -static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Decode a named_value_float message into a struct - * - * @param msg The message to decode - * @param named_value_float C-struct to decode the message contents into - */ -static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - named_value_float->time_boot_ms = mavlink_msg_named_value_float_get_time_boot_ms(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN? msg->len : MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN; - memset(named_value_float, 0, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); - memcpy(named_value_float, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_named_value_int.h b/include/mavlink/v2.0/common/mavlink_msg_named_value_int.h deleted file mode 100644 index b0b3b96..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_named_value_int.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE NAMED_VALUE_INT PACKING - -#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252 - -MAVPACKED( -typedef struct __mavlink_named_value_int_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int32_t value; /*< Signed integer value*/ - char name[10]; /*< Name of the debug variable*/ -}) mavlink_named_value_int_t; - -#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 -#define MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN 18 -#define MAVLINK_MSG_ID_252_LEN 18 -#define MAVLINK_MSG_ID_252_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ - 252, \ - "NAMED_VALUE_INT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ - "NAMED_VALUE_INT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ - } \ -} -#endif - -/** - * @brief Pack a named_value_int 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_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, const char *name, int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -} - -/** - * @brief Pack a named_value_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,const char *name,int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -} - -/** - * @brief Encode a named_value_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param named_value_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) -{ - return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); -} - -/** - * @brief Encode a named_value_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param named_value_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) -{ - return mavlink_msg_named_value_int_pack_chan(system_id, component_id, chan, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); -} - -/** - * @brief Send a named_value_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#endif -} - -/** - * @brief Send a named_value_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_named_value_int_send_struct(mavlink_channel_t chan, const mavlink_named_value_int_t* named_value_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_named_value_int_send(chan, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)named_value_int, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_named_value_int_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#else - mavlink_named_value_int_t *packet = (mavlink_named_value_int_t *)msgbuf; - 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, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE NAMED_VALUE_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from named_value_int message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field name from named_value_int message - * - * @return Name of the debug variable - */ -static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 8); -} - -/** - * @brief Get field value from named_value_int message - * - * @return Signed integer value - */ -static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Decode a named_value_int message into a struct - * - * @param msg The message to decode - * @param named_value_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - named_value_int->time_boot_ms = mavlink_msg_named_value_int_get_time_boot_ms(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN? msg->len : MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN; - memset(named_value_int, 0, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); - memcpy(named_value_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_nav_controller_output.h b/include/mavlink/v2.0/common/mavlink_msg_nav_controller_output.h deleted file mode 100644 index 5f2d40f..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_nav_controller_output.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE NAV_CONTROLLER_OUTPUT PACKING - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 - -MAVPACKED( -typedef struct __mavlink_nav_controller_output_t { - float nav_roll; /*< Current desired roll in degrees*/ - float nav_pitch; /*< Current desired pitch in degrees*/ - float alt_error; /*< Current altitude error in meters*/ - float aspd_error; /*< Current airspeed error in meters/second*/ - float xtrack_error; /*< Current crosstrack error on x-y plane in meters*/ - int16_t nav_bearing; /*< Current desired heading in degrees*/ - int16_t target_bearing; /*< Bearing to current MISSION/target in degrees*/ - uint16_t wp_dist; /*< Distance to active MISSION in meters*/ -}) mavlink_nav_controller_output_t; - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN 26 -#define MAVLINK_MSG_ID_62_LEN 26 -#define MAVLINK_MSG_ID_62_MIN_LEN 26 - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183 -#define MAVLINK_MSG_ID_62_CRC 183 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ - 62, \ - "NAV_CONTROLLER_OUTPUT", \ - 8, \ - { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ - { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ - { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ - { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ - { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ - { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ - { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ - { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ - "NAV_CONTROLLER_OUTPUT", \ - 8, \ - { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ - { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ - { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ - { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ - { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ - { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ - { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ - { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ - } \ -} -#endif - -/** - * @brief Pack a nav_controller_output 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 nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - - 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; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - packet.target_bearing = target_bearing; - packet.wp_dist = wp_dist; - - 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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -} - -/** - * @brief Pack a nav_controller_output message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - - 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; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - packet.target_bearing = target_bearing; - packet.wp_dist = wp_dist; - - 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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -} - -/** - * @brief Encode a nav_controller_output struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param nav_controller_output C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) -{ - return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); -} - -/** - * @brief Encode a nav_controller_output struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param nav_controller_output C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_nav_controller_output_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) -{ - return mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, chan, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); -} - -/** - * @brief Send a nav_controller_output message - * @param chan MAVLink channel to send the message - * - * @param nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - mavlink_nav_controller_output_t packet; - packet.nav_roll = nav_roll; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - 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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#endif -} - -/** - * @brief Send a nav_controller_output message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_nav_controller_output_send_struct(mavlink_channel_t chan, const mavlink_nav_controller_output_t* nav_controller_output) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_nav_controller_output_send(chan, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)nav_controller_output, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_float(buf, 0, nav_roll); - _mav_put_float(buf, 4, nav_pitch); - _mav_put_float(buf, 8, alt_error); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - mavlink_nav_controller_output_t *packet = (mavlink_nav_controller_output_t *)msgbuf; - packet->nav_roll = nav_roll; - packet->nav_pitch = nav_pitch; - packet->alt_error = alt_error; - packet->aspd_error = aspd_error; - packet->xtrack_error = xtrack_error; - packet->nav_bearing = nav_bearing; - 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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING - - -/** - * @brief Get field nav_roll from nav_controller_output message - * - * @return Current desired roll in degrees - */ -static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field nav_pitch from nav_controller_output message - * - * @return Current desired pitch in degrees - */ -static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field nav_bearing from nav_controller_output message - * - * @return Current desired heading in degrees - */ -static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field target_bearing from nav_controller_output message - * - * @return Bearing to current MISSION/target in degrees - */ -static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field wp_dist from nav_controller_output message - * - * @return Distance to active MISSION in meters - */ -static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field alt_error from nav_controller_output message - * - * @return Current altitude error in meters - */ -static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field aspd_error from nav_controller_output message - * - * @return Current airspeed error in meters/second - */ -static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field xtrack_error from nav_controller_output message - * - * @return Current crosstrack error on x-y plane in meters - */ -static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a nav_controller_output message into a struct - * - * @param msg The message to decode - * @param nav_controller_output C-struct to decode the message contents into - */ -static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg); - nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg); - nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg); - nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg); - nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg); - nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN? msg->len : MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN; - memset(nav_controller_output, 0, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); - memcpy(nav_controller_output, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_optical_flow.h b/include/mavlink/v2.0/common/mavlink_msg_optical_flow.h deleted file mode 100644 index b7bff06..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_optical_flow.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE OPTICAL_FLOW PACKING - -#define MAVLINK_MSG_ID_OPTICAL_FLOW 100 - -MAVPACKED( -typedef struct __mavlink_optical_flow_t { - uint64_t time_usec; /*< Timestamp (UNIX)*/ - float flow_comp_m_x; /*< Flow in meters in x-sensor direction, angular-speed compensated*/ - float flow_comp_m_y; /*< Flow in meters in y-sensor direction, angular-speed compensated*/ - float ground_distance; /*< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance*/ - int16_t flow_x; /*< Flow in pixels * 10 in x-sensor direction (dezi-pixels)*/ - int16_t flow_y; /*< Flow in pixels * 10 in y-sensor direction (dezi-pixels)*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: bad, 255: maximum quality*/ - float flow_rate_x; /*< Flow rate in radians/second about X axis*/ - float flow_rate_y; /*< Flow rate in radians/second about Y axis*/ -}) mavlink_optical_flow_t; - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 34 -#define MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN 26 -#define MAVLINK_MSG_ID_100_LEN 34 -#define MAVLINK_MSG_ID_100_MIN_LEN 26 - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 -#define MAVLINK_MSG_ID_100_CRC 175 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ - 100, \ - "OPTICAL_FLOW", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ - { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ - { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ - { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ - { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ - { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ - { "flow_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_optical_flow_t, flow_rate_x) }, \ - { "flow_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_optical_flow_t, flow_rate_y) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ - "OPTICAL_FLOW", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ - { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ - { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ - { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ - { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ - { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ - { "flow_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_optical_flow_t, flow_rate_x) }, \ - { "flow_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_optical_flow_t, flow_rate_y) }, \ - } \ -} -#endif - -/** - * @brief Pack a optical_flow 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 (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - * @param flow_rate_x Flow rate in radians/second about X axis - * @param flow_rate_y Flow rate in radians/second about Y axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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, float flow_rate_x, float flow_rate_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - _mav_put_float(buf, 26, flow_rate_x); - _mav_put_float(buf, 30, flow_rate_y); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - packet.flow_rate_x = flow_rate_x; - packet.flow_rate_y = flow_rate_y; - - 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, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -} - -/** - * @brief Pack a optical_flow message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - * @param flow_rate_x Flow rate in radians/second about X axis - * @param flow_rate_y Flow rate in radians/second about Y axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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,float flow_rate_x,float flow_rate_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - _mav_put_float(buf, 26, flow_rate_x); - _mav_put_float(buf, 30, flow_rate_y); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - packet.flow_rate_x = flow_rate_x; - packet.flow_rate_y = flow_rate_y; - - 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, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -} - -/** - * @brief Encode a optical_flow struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) -{ - return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y); -} - -/** - * @brief Encode a optical_flow struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) -{ - return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y); -} - -/** - * @brief Send a optical_flow message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - * @param flow_rate_x Flow rate in radians/second about X axis - * @param flow_rate_y Flow rate in radians/second about Y axis - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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, float flow_rate_x, float flow_rate_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - _mav_put_float(buf, 26, flow_rate_x); - _mav_put_float(buf, 30, flow_rate_y); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - packet.flow_rate_x = flow_rate_x; - packet.flow_rate_y = flow_rate_y; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#endif -} - -/** - * @brief Send a optical_flow message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_optical_flow_send_struct(mavlink_channel_t chan, const mavlink_optical_flow_t* optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_optical_flow_send(chan, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)optical_flow, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, 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, float flow_rate_x, float flow_rate_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - _mav_put_float(buf, 26, flow_rate_x); - _mav_put_float(buf, 30, flow_rate_y); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - mavlink_optical_flow_t *packet = (mavlink_optical_flow_t *)msgbuf; - packet->time_usec = time_usec; - packet->flow_comp_m_x = flow_comp_m_x; - packet->flow_comp_m_y = flow_comp_m_y; - packet->ground_distance = ground_distance; - packet->flow_x = flow_x; - packet->flow_y = flow_y; - packet->sensor_id = sensor_id; - packet->quality = quality; - packet->flow_rate_x = flow_rate_x; - packet->flow_rate_y = flow_rate_y; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPTICAL_FLOW UNPACKING - - -/** - * @brief Get field time_usec from optical_flow message - * - * @return Timestamp (UNIX) - */ -static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from optical_flow message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field flow_x from optical_flow message - * - * @return Flow in pixels * 10 in x-sensor direction (dezi-pixels) - */ -static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field flow_y from optical_flow message - * - * @return Flow in pixels * 10 in y-sensor direction (dezi-pixels) - */ -static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field flow_comp_m_x from optical_flow message - * - * @return Flow in meters in x-sensor direction, angular-speed compensated - */ -static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field flow_comp_m_y from optical_flow message - * - * @return Flow in meters in y-sensor direction, angular-speed compensated - */ -static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field quality from optical_flow message - * - * @return Optical flow quality / confidence. 0: bad, 255: maximum quality - */ -static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field ground_distance from optical_flow message - * - * @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - */ -static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field flow_rate_x from optical_flow message - * - * @return Flow rate in radians/second about X axis - */ -static inline float mavlink_msg_optical_flow_get_flow_rate_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 26); -} - -/** - * @brief Get field flow_rate_y from optical_flow message - * - * @return Flow rate in radians/second about Y axis - */ -static inline float mavlink_msg_optical_flow_get_flow_rate_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 30); -} - -/** - * @brief Decode a optical_flow message into a struct - * - * @param msg The message to decode - * @param optical_flow C-struct to decode the message contents into - */ -static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg); - optical_flow->flow_comp_m_x = mavlink_msg_optical_flow_get_flow_comp_m_x(msg); - optical_flow->flow_comp_m_y = mavlink_msg_optical_flow_get_flow_comp_m_y(msg); - optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg); - optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg); - optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg); - optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg); - optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg); - optical_flow->flow_rate_x = mavlink_msg_optical_flow_get_flow_rate_x(msg); - optical_flow->flow_rate_y = mavlink_msg_optical_flow_get_flow_rate_y(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPTICAL_FLOW_LEN? msg->len : MAVLINK_MSG_ID_OPTICAL_FLOW_LEN; - memset(optical_flow, 0, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); - memcpy(optical_flow, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_optical_flow_rad.h b/include/mavlink/v2.0/common/mavlink_msg_optical_flow_rad.h deleted file mode 100644 index c4326eb..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_optical_flow_rad.h +++ /dev/null @@ -1,488 +0,0 @@ -#pragma once -// MESSAGE OPTICAL_FLOW_RAD PACKING - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD 106 - -MAVPACKED( -typedef struct __mavlink_optical_flow_rad_t { - uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ - float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ - float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ - float integrated_xgyro; /*< RH rotation around X axis (rad)*/ - float integrated_ygyro; /*< RH rotation around Y axis (rad)*/ - float integrated_zgyro; /*< RH rotation around Z axis (rad)*/ - uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/ - float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/ - int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ -}) mavlink_optical_flow_rad_t; - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN 44 -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN 44 -#define MAVLINK_MSG_ID_106_LEN 44 -#define MAVLINK_MSG_ID_106_MIN_LEN 44 - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC 138 -#define MAVLINK_MSG_ID_106_CRC 138 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD { \ - 106, \ - "OPTICAL_FLOW_RAD", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD { \ - "OPTICAL_FLOW_RAD", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ - } \ -} -#endif - -/** - * @brief Pack a optical_flow_rad 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 sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_rad_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#else - mavlink_optical_flow_rad_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -} - -/** - * @brief Pack a optical_flow_rad message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_rad_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_id,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#else - mavlink_optical_flow_rad_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -} - -/** - * @brief Encode a optical_flow_rad struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param optical_flow_rad C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_rad_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad) -{ - return mavlink_msg_optical_flow_rad_pack(system_id, component_id, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); -} - -/** - * @brief Encode a optical_flow_rad struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param optical_flow_rad C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_rad_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad) -{ - return mavlink_msg_optical_flow_rad_pack_chan(system_id, component_id, chan, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); -} - -/** - * @brief Send a optical_flow_rad message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro RH rotation around X axis (rad) - * @param integrated_ygyro RH rotation around Y axis (rad) - * @param integrated_zgyro RH rotation around Z axis (rad) - * @param temperature Temperature * 100 in centi-degrees Celsius - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us Time in microseconds since the distance was sampled. - * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_optical_flow_rad_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#else - mavlink_optical_flow_rad_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#endif -} - -/** - * @brief Send a optical_flow_rad message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_optical_flow_rad_send_struct(mavlink_channel_t chan, const mavlink_optical_flow_rad_t* optical_flow_rad) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_optical_flow_rad_send(chan, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)optical_flow_rad, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_optical_flow_rad_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#else - mavlink_optical_flow_rad_t *packet = (mavlink_optical_flow_rad_t *)msgbuf; - packet->time_usec = time_usec; - packet->integration_time_us = integration_time_us; - packet->integrated_x = integrated_x; - packet->integrated_y = integrated_y; - packet->integrated_xgyro = integrated_xgyro; - packet->integrated_ygyro = integrated_ygyro; - packet->integrated_zgyro = integrated_zgyro; - packet->time_delta_distance_us = time_delta_distance_us; - packet->distance = distance; - packet->temperature = temperature; - packet->sensor_id = sensor_id; - packet->quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPTICAL_FLOW_RAD UNPACKING - - -/** - * @brief Get field time_usec from optical_flow_rad message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_optical_flow_rad_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from optical_flow_rad message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_optical_flow_rad_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field integration_time_us from optical_flow_rad message - * - * @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - */ -static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field integrated_x from optical_flow_rad message - * - * @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field integrated_y from optical_flow_rad message - * - * @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field integrated_xgyro from optical_flow_rad message - * - * @return RH rotation around X axis (rad) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field integrated_ygyro from optical_flow_rad message - * - * @return RH rotation around Y axis (rad) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field integrated_zgyro from optical_flow_rad message - * - * @return RH rotation around Z axis (rad) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field temperature from optical_flow_rad message - * - * @return Temperature * 100 in centi-degrees Celsius - */ -static inline int16_t mavlink_msg_optical_flow_rad_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 40); -} - -/** - * @brief Get field quality from optical_flow_rad message - * - * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - */ -static inline uint8_t mavlink_msg_optical_flow_rad_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 43); -} - -/** - * @brief Get field time_delta_distance_us from optical_flow_rad message - * - * @return Time in microseconds since the distance was sampled. - */ -static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 32); -} - -/** - * @brief Get field distance from optical_flow_rad message - * - * @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -static inline float mavlink_msg_optical_flow_rad_get_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a optical_flow_rad message into a struct - * - * @param msg The message to decode - * @param optical_flow_rad C-struct to decode the message contents into - */ -static inline void mavlink_msg_optical_flow_rad_decode(const mavlink_message_t* msg, mavlink_optical_flow_rad_t* optical_flow_rad) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - optical_flow_rad->time_usec = mavlink_msg_optical_flow_rad_get_time_usec(msg); - optical_flow_rad->integration_time_us = mavlink_msg_optical_flow_rad_get_integration_time_us(msg); - optical_flow_rad->integrated_x = mavlink_msg_optical_flow_rad_get_integrated_x(msg); - optical_flow_rad->integrated_y = mavlink_msg_optical_flow_rad_get_integrated_y(msg); - optical_flow_rad->integrated_xgyro = mavlink_msg_optical_flow_rad_get_integrated_xgyro(msg); - optical_flow_rad->integrated_ygyro = mavlink_msg_optical_flow_rad_get_integrated_ygyro(msg); - optical_flow_rad->integrated_zgyro = mavlink_msg_optical_flow_rad_get_integrated_zgyro(msg); - optical_flow_rad->time_delta_distance_us = mavlink_msg_optical_flow_rad_get_time_delta_distance_us(msg); - optical_flow_rad->distance = mavlink_msg_optical_flow_rad_get_distance(msg); - optical_flow_rad->temperature = mavlink_msg_optical_flow_rad_get_temperature(msg); - optical_flow_rad->sensor_id = mavlink_msg_optical_flow_rad_get_sensor_id(msg); - optical_flow_rad->quality = mavlink_msg_optical_flow_rad_get_quality(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN? msg->len : MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN; - memset(optical_flow_rad, 0, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); - memcpy(optical_flow_rad, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_param_map_rc.h b/include/mavlink/v2.0/common/mavlink_msg_param_map_rc.h deleted file mode 100644 index 5b64b7f..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_param_map_rc.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE PARAM_MAP_RC PACKING - -#define MAVLINK_MSG_ID_PARAM_MAP_RC 50 - -MAVPACKED( -typedef struct __mavlink_param_map_rc_t { - float param_value0; /*< Initial parameter value*/ - float scale; /*< Scale, maps the RC range [-1, 1] to a parameter value*/ - float param_value_min; /*< Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)*/ - float param_value_max; /*< Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)*/ - int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t parameter_rc_channel_index; /*< Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.*/ -}) mavlink_param_map_rc_t; - -#define MAVLINK_MSG_ID_PARAM_MAP_RC_LEN 37 -#define MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN 37 -#define MAVLINK_MSG_ID_50_LEN 37 -#define MAVLINK_MSG_ID_50_MIN_LEN 37 - -#define MAVLINK_MSG_ID_PARAM_MAP_RC_CRC 78 -#define MAVLINK_MSG_ID_50_CRC 78 - -#define MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \ - 50, \ - "PARAM_MAP_RC", \ - 9, \ - { { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ - { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \ - { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \ - { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ - { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \ - "PARAM_MAP_RC", \ - 9, \ - { { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ - { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \ - { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \ - { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ - { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_map_rc message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_map_rc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#else - mavlink_param_map_rc_t packet; - packet.param_value0 = param_value0; - packet.scale = scale; - packet.param_value_min = param_value_min; - packet.param_value_max = param_value_max; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -} - -/** - * @brief Pack a param_map_rc message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_map_rc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index,uint8_t parameter_rc_channel_index,float param_value0,float scale,float param_value_min,float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#else - mavlink_param_map_rc_t packet; - packet.param_value0 = param_value0; - packet.scale = scale; - packet.param_value_min = param_value_min; - packet.param_value_max = param_value_max; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -} - -/** - * @brief Encode a param_map_rc struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_map_rc C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_map_rc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc) -{ - return mavlink_msg_param_map_rc_pack(system_id, component_id, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); -} - -/** - * @brief Encode a param_map_rc struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_map_rc C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_map_rc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc) -{ - return mavlink_msg_param_map_rc_pack_chan(system_id, component_id, chan, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); -} - -/** - * @brief Send a param_map_rc message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_map_rc_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#else - mavlink_param_map_rc_t packet; - packet.param_value0 = param_value0; - packet.scale = scale; - packet.param_value_min = param_value_min; - packet.param_value_max = param_value_max; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)&packet, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#endif -} - -/** - * @brief Send a param_map_rc message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_map_rc_send_struct(mavlink_channel_t chan, const mavlink_param_map_rc_t* param_map_rc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_map_rc_send(chan, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)param_map_rc, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_MAP_RC_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_map_rc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#else - mavlink_param_map_rc_t *packet = (mavlink_param_map_rc_t *)msgbuf; - packet->param_value0 = param_value0; - packet->scale = scale; - packet->param_value_min = param_value_min; - packet->param_value_max = param_value_max; - packet->param_index = param_index; - packet->target_system = target_system; - packet->target_component = target_component; - packet->parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)packet, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_MAP_RC UNPACKING - - -/** - * @brief Get field target_system from param_map_rc message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_map_rc_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field target_component from param_map_rc message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_map_rc_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 19); -} - -/** - * @brief Get field param_id from param_map_rc message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_map_rc_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 20); -} - -/** - * @brief Get field param_index from param_map_rc message - * - * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - */ -static inline int16_t mavlink_msg_param_map_rc_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field parameter_rc_channel_index from param_map_rc message - * - * @return Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - */ -static inline uint8_t mavlink_msg_param_map_rc_get_parameter_rc_channel_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field param_value0 from param_map_rc message - * - * @return Initial parameter value - */ -static inline float mavlink_msg_param_map_rc_get_param_value0(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field scale from param_map_rc message - * - * @return Scale, maps the RC range [-1, 1] to a parameter value - */ -static inline float mavlink_msg_param_map_rc_get_scale(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param_value_min from param_map_rc message - * - * @return Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - */ -static inline float mavlink_msg_param_map_rc_get_param_value_min(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param_value_max from param_map_rc message - * - * @return Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - */ -static inline float mavlink_msg_param_map_rc_get_param_value_max(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a param_map_rc message into a struct - * - * @param msg The message to decode - * @param param_map_rc C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_map_rc_decode(const mavlink_message_t* msg, mavlink_param_map_rc_t* param_map_rc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_map_rc->param_value0 = mavlink_msg_param_map_rc_get_param_value0(msg); - param_map_rc->scale = mavlink_msg_param_map_rc_get_scale(msg); - param_map_rc->param_value_min = mavlink_msg_param_map_rc_get_param_value_min(msg); - param_map_rc->param_value_max = mavlink_msg_param_map_rc_get_param_value_max(msg); - param_map_rc->param_index = mavlink_msg_param_map_rc_get_param_index(msg); - param_map_rc->target_system = mavlink_msg_param_map_rc_get_target_system(msg); - param_map_rc->target_component = mavlink_msg_param_map_rc_get_target_component(msg); - mavlink_msg_param_map_rc_get_param_id(msg, param_map_rc->param_id); - param_map_rc->parameter_rc_channel_index = mavlink_msg_param_map_rc_get_parameter_rc_channel_index(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_MAP_RC_LEN? msg->len : MAVLINK_MSG_ID_PARAM_MAP_RC_LEN; - memset(param_map_rc, 0, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); - memcpy(param_map_rc, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_param_request_list.h b/include/mavlink/v2.0/common/mavlink_msg_param_request_list.h deleted file mode 100644 index 2c5da24..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_param_request_list.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE PARAM_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 - -MAVPACKED( -typedef struct __mavlink_param_request_list_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_param_request_list_t; - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN 2 -#define MAVLINK_MSG_ID_21_LEN 2 -#define MAVLINK_MSG_ID_21_MIN_LEN 2 - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC 159 -#define MAVLINK_MSG_ID_21_CRC 159 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ - 21, \ - "PARAM_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ - "PARAM_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -} - -/** - * @brief Pack a param_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -} - -/** - * @brief Encode a param_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) -{ - return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component); -} - -/** - * @brief Encode a param_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) -{ - return mavlink_msg_param_request_list_pack_chan(system_id, component_id, chan, msg, param_request_list->target_system, param_request_list->target_component); -} - -/** - * @brief Send a param_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#endif -} - -/** - * @brief Send a param_request_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_request_list_send_struct(mavlink_channel_t chan, const mavlink_param_request_list_t* param_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_request_list_send(chan, param_request_list->target_system, param_request_list->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)param_request_list, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#else - mavlink_param_request_list_t *packet = (mavlink_param_request_list_t *)msgbuf; - 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, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from param_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from param_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a param_request_list message into a struct - * - * @param msg The message to decode - * @param param_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN; - memset(param_request_list, 0, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); - memcpy(param_request_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_param_request_read.h b/include/mavlink/v2.0/common/mavlink_msg_param_request_read.h deleted file mode 100644 index 5381596..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_param_request_read.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE PARAM_REQUEST_READ PACKING - -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 - -MAVPACKED( -typedef struct __mavlink_param_request_read_t { - int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ -}) mavlink_param_request_read_t; - -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN 20 -#define MAVLINK_MSG_ID_20_LEN 20 -#define MAVLINK_MSG_ID_20_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ - 20, \ - "PARAM_REQUEST_READ", \ - 4, \ - { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ - "PARAM_REQUEST_READ", \ - 4, \ - { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_request_read message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, 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, 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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -} - -/** - * @brief Pack a param_request_read message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, 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, 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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -} - -/** - * @brief Encode a param_request_read struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_request_read C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) -{ - return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); -} - -/** - * @brief Encode a param_request_read struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_request_read C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) -{ - return mavlink_msg_param_request_read_pack_chan(system_id, component_id, chan, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); -} - -/** - * @brief Send a param_request_read message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#endif -} - -/** - * @brief Send a param_request_read message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_request_read_send_struct(mavlink_channel_t chan, const mavlink_param_request_read_t* param_request_read) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_request_read_send(chan, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)param_request_read, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_request_read_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#else - mavlink_param_request_read_t *packet = (mavlink_param_request_read_t *)msgbuf; - 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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_REQUEST_READ UNPACKING - - -/** - * @brief Get field target_system from param_request_read message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from param_request_read message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field param_id from param_request_read message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 4); -} - -/** - * @brief Get field param_index from param_request_read message - * - * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - */ -static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Decode a param_request_read message into a struct - * - * @param msg The message to decode - * @param param_request_read C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg); - param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN? msg->len : MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN; - memset(param_request_read, 0, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); - memcpy(param_request_read, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_param_set.h b/include/mavlink/v2.0/common/mavlink_msg_param_set.h deleted file mode 100644 index cc73109..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_param_set.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE PARAM_SET PACKING - -#define MAVLINK_MSG_ID_PARAM_SET 23 - -MAVPACKED( -typedef struct __mavlink_param_set_t { - float param_value; /*< Onboard parameter value*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/ -}) mavlink_param_set_t; - -#define MAVLINK_MSG_ID_PARAM_SET_LEN 23 -#define MAVLINK_MSG_ID_PARAM_SET_MIN_LEN 23 -#define MAVLINK_MSG_ID_23_LEN 23 -#define MAVLINK_MSG_ID_23_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_SET { \ - 23, \ - "PARAM_SET", \ - 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_SET { \ - "PARAM_SET", \ - 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_set message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PARAM_SET_LEN); -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - 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, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_SET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -} - -/** - * @brief Pack a param_set message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PARAM_SET_LEN); -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - 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, 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, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -} - -/** - * @brief Encode a param_set struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set) -{ - return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); -} - -/** - * @brief Encode a param_set struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_set_t* param_set) -{ - return mavlink_msg_param_set_pack_chan(system_id, component_id, chan, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); -} - -/** - * @brief Send a param_set message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - 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, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#endif -} - -/** - * @brief Send a param_set message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_set_send_struct(mavlink_channel_t chan, const mavlink_param_set_t* param_set) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_set_send(chan, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)param_set, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 22, param_type); - _mav_put_char_array(buf, 6, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - mavlink_param_set_t *packet = (mavlink_param_set_t *)msgbuf; - packet->param_value = param_value; - packet->target_system = target_system; - 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, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_SET UNPACKING - - -/** - * @brief Get field target_system from param_set message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from param_set message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field param_id from param_set message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 6); -} - -/** - * @brief Get field param_value from param_set message - * - * @return Onboard parameter value - */ -static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param_type from param_set message - * - * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - */ -static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Decode a param_set message into a struct - * - * @param msg The message to decode - * @param param_set C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_set->param_value = mavlink_msg_param_set_get_param_value(msg); - param_set->target_system = mavlink_msg_param_set_get_target_system(msg); - param_set->target_component = mavlink_msg_param_set_get_target_component(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_SET_LEN? msg->len : MAVLINK_MSG_ID_PARAM_SET_LEN; - memset(param_set, 0, MAVLINK_MSG_ID_PARAM_SET_LEN); - memcpy(param_set, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_param_value.h b/include/mavlink/v2.0/common/mavlink_msg_param_value.h deleted file mode 100644 index e2cb891..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_param_value.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE PARAM_VALUE PACKING - -#define MAVLINK_MSG_ID_PARAM_VALUE 22 - -MAVPACKED( -typedef struct __mavlink_param_value_t { - float param_value; /*< Onboard parameter value*/ - uint16_t param_count; /*< Total number of onboard parameters*/ - uint16_t param_index; /*< Index of this onboard parameter*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/ -}) mavlink_param_value_t; - -#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 -#define MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN 25 -#define MAVLINK_MSG_ID_22_LEN 25 -#define MAVLINK_MSG_ID_22_MIN_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 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ - 22, \ - "PARAM_VALUE", \ - 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ - { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ - { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ - "PARAM_VALUE", \ - 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ - { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ - { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_value 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 param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - 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, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -} - -/** - * @brief Pack a param_value message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - 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, 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, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -} - -/** - * @brief Encode a param_value struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_value C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value) -{ - return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); -} - -/** - * @brief Encode a param_value struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_value C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_value_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_value_t* param_value) -{ - return mavlink_msg_param_value_pack_chan(system_id, component_id, chan, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); -} - -/** - * @brief Send a param_value message - * @param chan MAVLink channel to send the message - * - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - 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, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#endif -} - -/** - * @brief Send a param_value message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_value_send_struct(mavlink_channel_t chan, const mavlink_param_value_t* param_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_value_send(chan, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)param_value, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_VALUE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_value_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - mavlink_param_value_t *packet = (mavlink_param_value_t *)msgbuf; - packet->param_value = param_value; - packet->param_count = param_count; - 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, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_VALUE UNPACKING - - -/** - * @brief Get field param_id from param_value message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 8); -} - -/** - * @brief Get field param_value from param_value message - * - * @return Onboard parameter value - */ -static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param_type from param_value message - * - * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - */ -static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field param_count from param_value message - * - * @return Total number of onboard parameters - */ -static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field param_index from param_value message - * - * @return Index of this onboard parameter - */ -static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Decode a param_value message into a struct - * - * @param msg The message to decode - * @param param_value C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_value->param_value = mavlink_msg_param_value_get_param_value(msg); - param_value->param_count = mavlink_msg_param_value_get_param_count(msg); - param_value->param_index = mavlink_msg_param_value_get_param_index(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 - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_VALUE_LEN? msg->len : MAVLINK_MSG_ID_PARAM_VALUE_LEN; - memset(param_value, 0, MAVLINK_MSG_ID_PARAM_VALUE_LEN); - memcpy(param_value, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_ping.h b/include/mavlink/v2.0/common/mavlink_msg_ping.h deleted file mode 100644 index 1e18bc6..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_ping.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE PING PACKING - -#define MAVLINK_MSG_ID_PING 4 - -MAVPACKED( -typedef struct __mavlink_ping_t { - uint64_t time_usec; /*< Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)*/ - uint32_t seq; /*< PING sequence*/ - uint8_t target_system; /*< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system*/ - uint8_t target_component; /*< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system*/ -}) mavlink_ping_t; - -#define MAVLINK_MSG_ID_PING_LEN 14 -#define MAVLINK_MSG_ID_PING_MIN_LEN 14 -#define MAVLINK_MSG_ID_4_LEN 14 -#define MAVLINK_MSG_ID_4_MIN_LEN 14 - -#define MAVLINK_MSG_ID_PING_CRC 237 -#define MAVLINK_MSG_ID_4_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PING { \ - 4, \ - "PING", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PING { \ - "PING", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a ping 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 Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PING_LEN); -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -} - -/** - * @brief Pack a ping message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_PING_LEN); -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -} - -/** - * @brief Encode a ping struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param ping C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping) -{ - return mavlink_msg_ping_pack(system_id, component_id, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); -} - -/** - * @brief Encode a ping struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ping C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ping_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_t* ping) -{ - return mavlink_msg_ping_pack_chan(system_id, component_id, chan, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); -} - -/** - * @brief Send a ping message - * @param chan MAVLink channel to send the message - * - * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#endif -} - -/** - * @brief Send a ping message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_ping_send_struct(mavlink_channel_t chan, const mavlink_ping_t* ping) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_ping_send(chan, ping->time_usec, ping->seq, ping->target_system, ping->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)ping, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PING_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_ping_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - mavlink_ping_t *packet = (mavlink_ping_t *)msgbuf; - packet->time_usec = time_usec; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PING UNPACKING - - -/** - * @brief Get field time_usec from ping message - * - * @return Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - */ -static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field seq from ping message - * - * @return PING sequence - */ -static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field target_system from ping message - * - * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - */ -static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field target_component from ping message - * - * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - */ -static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Decode a ping message into a struct - * - * @param msg The message to decode - * @param ping C-struct to decode the message contents into - */ -static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - ping->time_usec = mavlink_msg_ping_get_time_usec(msg); - ping->seq = mavlink_msg_ping_get_seq(msg); - ping->target_system = mavlink_msg_ping_get_target_system(msg); - ping->target_component = mavlink_msg_ping_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PING_LEN? msg->len : MAVLINK_MSG_ID_PING_LEN; - memset(ping, 0, MAVLINK_MSG_ID_PING_LEN); - memcpy(ping, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_play_tune.h b/include/mavlink/v2.0/common/mavlink_msg_play_tune.h deleted file mode 100644 index d518373..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_play_tune.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE PLAY_TUNE PACKING - -#define MAVLINK_MSG_ID_PLAY_TUNE 258 - -MAVPACKED( -typedef struct __mavlink_play_tune_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char tune[30]; /*< tune in board specific format*/ -}) mavlink_play_tune_t; - -#define MAVLINK_MSG_ID_PLAY_TUNE_LEN 32 -#define MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN 32 -#define MAVLINK_MSG_ID_258_LEN 32 -#define MAVLINK_MSG_ID_258_MIN_LEN 32 - -#define MAVLINK_MSG_ID_PLAY_TUNE_CRC 187 -#define MAVLINK_MSG_ID_258_CRC 187 - -#define MAVLINK_MSG_PLAY_TUNE_FIELD_TUNE_LEN 30 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PLAY_TUNE { \ - 258, \ - "PLAY_TUNE", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_play_tune_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_play_tune_t, target_component) }, \ - { "tune", NULL, MAVLINK_TYPE_CHAR, 30, 2, offsetof(mavlink_play_tune_t, tune) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PLAY_TUNE { \ - "PLAY_TUNE", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_play_tune_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_play_tune_t, target_component) }, \ - { "tune", NULL, MAVLINK_TYPE_CHAR, 30, 2, offsetof(mavlink_play_tune_t, tune) }, \ - } \ -} -#endif - -/** - * @brief Pack a play_tune message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param tune tune in board specific format - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_play_tune_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const char *tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PLAY_TUNE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_char_array(buf, 2, tune, 30); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PLAY_TUNE_LEN); -#else - mavlink_play_tune_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.tune, tune, sizeof(char)*30); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PLAY_TUNE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PLAY_TUNE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -} - -/** - * @brief Pack a play_tune message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param tune tune in board specific format - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_play_tune_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const char *tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PLAY_TUNE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_char_array(buf, 2, tune, 30); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PLAY_TUNE_LEN); -#else - mavlink_play_tune_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.tune, tune, sizeof(char)*30); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PLAY_TUNE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PLAY_TUNE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -} - -/** - * @brief Encode a play_tune struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param play_tune C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_play_tune_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_play_tune_t* play_tune) -{ - return mavlink_msg_play_tune_pack(system_id, component_id, msg, play_tune->target_system, play_tune->target_component, play_tune->tune); -} - -/** - * @brief Encode a play_tune struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param play_tune C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_play_tune_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_play_tune_t* play_tune) -{ - return mavlink_msg_play_tune_pack_chan(system_id, component_id, chan, msg, play_tune->target_system, play_tune->target_component, play_tune->tune); -} - -/** - * @brief Send a play_tune message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param tune tune in board specific format - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_play_tune_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PLAY_TUNE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_char_array(buf, 2, tune, 30); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE, buf, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -#else - mavlink_play_tune_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.tune, tune, sizeof(char)*30); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE, (const char *)&packet, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -#endif -} - -/** - * @brief Send a play_tune message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_play_tune_send_struct(mavlink_channel_t chan, const mavlink_play_tune_t* play_tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_play_tune_send(chan, play_tune->target_system, play_tune->target_component, play_tune->tune); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE, (const char *)play_tune, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PLAY_TUNE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_play_tune_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_char_array(buf, 2, tune, 30); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE, buf, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -#else - mavlink_play_tune_t *packet = (mavlink_play_tune_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->tune, tune, sizeof(char)*30); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE, (const char *)packet, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PLAY_TUNE UNPACKING - - -/** - * @brief Get field target_system from play_tune message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_play_tune_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from play_tune message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_play_tune_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field tune from play_tune message - * - * @return tune in board specific format - */ -static inline uint16_t mavlink_msg_play_tune_get_tune(const mavlink_message_t* msg, char *tune) -{ - return _MAV_RETURN_char_array(msg, tune, 30, 2); -} - -/** - * @brief Decode a play_tune message into a struct - * - * @param msg The message to decode - * @param play_tune C-struct to decode the message contents into - */ -static inline void mavlink_msg_play_tune_decode(const mavlink_message_t* msg, mavlink_play_tune_t* play_tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - play_tune->target_system = mavlink_msg_play_tune_get_target_system(msg); - play_tune->target_component = mavlink_msg_play_tune_get_target_component(msg); - mavlink_msg_play_tune_get_tune(msg, play_tune->tune); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PLAY_TUNE_LEN? msg->len : MAVLINK_MSG_ID_PLAY_TUNE_LEN; - memset(play_tune, 0, MAVLINK_MSG_ID_PLAY_TUNE_LEN); - memcpy(play_tune, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_position_target_global_int.h b/include/mavlink/v2.0/common/mavlink_msg_position_target_global_int.h deleted file mode 100644 index 160a5fa..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_position_target_global_int.h +++ /dev/null @@ -1,538 +0,0 @@ -#pragma once -// MESSAGE POSITION_TARGET_GLOBAL_INT PACKING - -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87 - -MAVPACKED( -typedef struct __mavlink_position_target_global_int_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ - int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/ - int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/ - float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ -}) mavlink_position_target_global_int_t; - -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51 -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN 51 -#define MAVLINK_MSG_ID_87_LEN 51 -#define MAVLINK_MSG_ID_87_MIN_LEN 51 - -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150 -#define MAVLINK_MSG_ID_87_CRC 150 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \ - 87, \ - "POSITION_TARGET_GLOBAL_INT", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \ - "POSITION_TARGET_GLOBAL_INT", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a position_target_global_int 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_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Pack a position_target_global_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Encode a position_target_global_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int) -{ - return mavlink_msg_position_target_global_int_pack(system_id, component_id, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); -} - -/** - * @brief Encode a position_target_global_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int) -{ - return mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, chan, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); -} - -/** - * @brief Send a position_target_global_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -/** - * @brief Send a position_target_global_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_position_target_global_int_send_struct(mavlink_channel_t chan, const mavlink_position_target_global_int_t* position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_position_target_global_int_send(chan, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)position_target_global_int, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_position_target_global_int_t *packet = (mavlink_position_target_global_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->lat_int = lat_int; - packet->lon_int = lon_int; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE POSITION_TARGET_GLOBAL_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from position_target_global_int message - * - * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - */ -static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field coordinate_frame from position_target_global_int message - * - * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - */ -static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field type_mask from position_target_global_int message - * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - */ -static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field lat_int from position_target_global_int message - * - * @return X Position in WGS84 frame in 1e7 * meters - */ -static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon_int from position_target_global_int message - * - * @return Y Position in WGS84 frame in 1e7 * meters - */ -static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt from position_target_global_int message - * - * @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - */ -static inline float mavlink_msg_position_target_global_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from position_target_global_int message - * - * @return X velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_global_int_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from position_target_global_int message - * - * @return Y velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_global_int_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from position_target_global_int message - * - * @return Z velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_global_int_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from position_target_global_int message - * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_global_int_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from position_target_global_int message - * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_global_int_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from position_target_global_int message - * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from position_target_global_int message - * - * @return yaw setpoint in rad - */ -static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from position_target_global_int message - * - * @return yaw rate setpoint in rad/s - */ -static inline float mavlink_msg_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a position_target_global_int message into a struct - * - * @param msg The message to decode - * @param position_target_global_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_position_target_global_int_t* position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - position_target_global_int->time_boot_ms = mavlink_msg_position_target_global_int_get_time_boot_ms(msg); - position_target_global_int->lat_int = mavlink_msg_position_target_global_int_get_lat_int(msg); - position_target_global_int->lon_int = mavlink_msg_position_target_global_int_get_lon_int(msg); - position_target_global_int->alt = mavlink_msg_position_target_global_int_get_alt(msg); - position_target_global_int->vx = mavlink_msg_position_target_global_int_get_vx(msg); - position_target_global_int->vy = mavlink_msg_position_target_global_int_get_vy(msg); - position_target_global_int->vz = mavlink_msg_position_target_global_int_get_vz(msg); - position_target_global_int->afx = mavlink_msg_position_target_global_int_get_afx(msg); - position_target_global_int->afy = mavlink_msg_position_target_global_int_get_afy(msg); - position_target_global_int->afz = mavlink_msg_position_target_global_int_get_afz(msg); - position_target_global_int->yaw = mavlink_msg_position_target_global_int_get_yaw(msg); - position_target_global_int->yaw_rate = mavlink_msg_position_target_global_int_get_yaw_rate(msg); - position_target_global_int->type_mask = mavlink_msg_position_target_global_int_get_type_mask(msg); - position_target_global_int->coordinate_frame = mavlink_msg_position_target_global_int_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN? msg->len : MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN; - memset(position_target_global_int, 0, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); - memcpy(position_target_global_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_position_target_local_ned.h b/include/mavlink/v2.0/common/mavlink_msg_position_target_local_ned.h deleted file mode 100644 index 3464e9a..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_position_target_local_ned.h +++ /dev/null @@ -1,538 +0,0 @@ -#pragma once -// MESSAGE POSITION_TARGET_LOCAL_NED PACKING - -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED 85 - -MAVPACKED( -typedef struct __mavlink_position_target_local_ned_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float x; /*< X Position in NED frame in meters*/ - float y; /*< Y Position in NED frame in meters*/ - float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ -}) mavlink_position_target_local_ned_t; - -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51 -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN 51 -#define MAVLINK_MSG_ID_85_LEN 51 -#define MAVLINK_MSG_ID_85_MIN_LEN 51 - -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 140 -#define MAVLINK_MSG_ID_85_CRC 140 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \ - 85, \ - "POSITION_TARGET_LOCAL_NED", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \ - "POSITION_TARGET_LOCAL_NED", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a position_target_local_ned 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_boot_ms Timestamp in milliseconds since system boot - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Pack a position_target_local_ned message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Encode a position_target_local_ned struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned) -{ - return mavlink_msg_position_target_local_ned_pack(system_id, component_id, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); -} - -/** - * @brief Encode a position_target_local_ned struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned) -{ - return mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); -} - -/** - * @brief Send a position_target_local_ned message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -/** - * @brief Send a position_target_local_ned message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_position_target_local_ned_send_struct(mavlink_channel_t chan, const mavlink_position_target_local_ned_t* position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_position_target_local_ned_send(chan, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)position_target_local_ned, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_position_target_local_ned_t *packet = (mavlink_position_target_local_ned_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE POSITION_TARGET_LOCAL_NED UNPACKING - - -/** - * @brief Get field time_boot_ms from position_target_local_ned message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field coordinate_frame from position_target_local_ned message - * - * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - */ -static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field type_mask from position_target_local_ned message - * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - */ -static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field x from position_target_local_ned message - * - * @return X Position in NED frame in meters - */ -static inline float mavlink_msg_position_target_local_ned_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from position_target_local_ned message - * - * @return Y Position in NED frame in meters - */ -static inline float mavlink_msg_position_target_local_ned_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from position_target_local_ned message - * - * @return Z Position in NED frame in meters (note, altitude is negative in NED) - */ -static inline float mavlink_msg_position_target_local_ned_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from position_target_local_ned message - * - * @return X velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_local_ned_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from position_target_local_ned message - * - * @return Y velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_local_ned_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from position_target_local_ned message - * - * @return Z velocity in NED frame in meter / s - */ -static inline float mavlink_msg_position_target_local_ned_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from position_target_local_ned message - * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_local_ned_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from position_target_local_ned message - * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_local_ned_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from position_target_local_ned message - * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from position_target_local_ned message - * - * @return yaw setpoint in rad - */ -static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from position_target_local_ned message - * - * @return yaw rate setpoint in rad/s - */ -static inline float mavlink_msg_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a position_target_local_ned message into a struct - * - * @param msg The message to decode - * @param position_target_local_ned C-struct to decode the message contents into - */ -static inline void mavlink_msg_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_position_target_local_ned_t* position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - position_target_local_ned->time_boot_ms = mavlink_msg_position_target_local_ned_get_time_boot_ms(msg); - position_target_local_ned->x = mavlink_msg_position_target_local_ned_get_x(msg); - position_target_local_ned->y = mavlink_msg_position_target_local_ned_get_y(msg); - position_target_local_ned->z = mavlink_msg_position_target_local_ned_get_z(msg); - position_target_local_ned->vx = mavlink_msg_position_target_local_ned_get_vx(msg); - position_target_local_ned->vy = mavlink_msg_position_target_local_ned_get_vy(msg); - position_target_local_ned->vz = mavlink_msg_position_target_local_ned_get_vz(msg); - position_target_local_ned->afx = mavlink_msg_position_target_local_ned_get_afx(msg); - position_target_local_ned->afy = mavlink_msg_position_target_local_ned_get_afy(msg); - position_target_local_ned->afz = mavlink_msg_position_target_local_ned_get_afz(msg); - position_target_local_ned->yaw = mavlink_msg_position_target_local_ned_get_yaw(msg); - position_target_local_ned->yaw_rate = mavlink_msg_position_target_local_ned_get_yaw_rate(msg); - position_target_local_ned->type_mask = mavlink_msg_position_target_local_ned_get_type_mask(msg); - position_target_local_ned->coordinate_frame = mavlink_msg_position_target_local_ned_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN? msg->len : MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN; - memset(position_target_local_ned, 0, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); - memcpy(position_target_local_ned, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_power_status.h b/include/mavlink/v2.0/common/mavlink_msg_power_status.h deleted file mode 100644 index dca62b5..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_power_status.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE POWER_STATUS PACKING - -#define MAVLINK_MSG_ID_POWER_STATUS 125 - -MAVPACKED( -typedef struct __mavlink_power_status_t { - uint16_t Vcc; /*< 5V rail voltage in millivolts*/ - uint16_t Vservo; /*< servo rail voltage in millivolts*/ - uint16_t flags; /*< power supply status flags (see MAV_POWER_STATUS enum)*/ -}) mavlink_power_status_t; - -#define MAVLINK_MSG_ID_POWER_STATUS_LEN 6 -#define MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN 6 -#define MAVLINK_MSG_ID_125_LEN 6 -#define MAVLINK_MSG_ID_125_MIN_LEN 6 - -#define MAVLINK_MSG_ID_POWER_STATUS_CRC 203 -#define MAVLINK_MSG_ID_125_CRC 203 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \ - 125, \ - "POWER_STATUS", \ - 3, \ - { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \ - { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \ - "POWER_STATUS", \ - 3, \ - { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \ - { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \ - } \ -} -#endif - -/** - * @brief Pack a power_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 Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -} - -/** - * @brief Pack a power_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_power_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t Vcc,uint16_t Vservo,uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -} - -/** - * @brief Encode a power_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param power_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_power_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_power_status_t* power_status) -{ - return mavlink_msg_power_status_pack(system_id, component_id, msg, power_status->Vcc, power_status->Vservo, power_status->flags); -} - -/** - * @brief Encode a power_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param power_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_power_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_power_status_t* power_status) -{ - return mavlink_msg_power_status_pack_chan(system_id, component_id, chan, msg, power_status->Vcc, power_status->Vservo, power_status->flags); -} - -/** - * @brief Send a power_status message - * @param chan MAVLink channel to send the message - * - * @param Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_power_status_send(mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#endif -} - -/** - * @brief Send a power_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_power_status_send_struct(mavlink_channel_t chan, const mavlink_power_status_t* power_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_power_status_send(chan, power_status->Vcc, power_status->Vservo, power_status->flags); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)power_status, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_POWER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_power_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - mavlink_power_status_t *packet = (mavlink_power_status_t *)msgbuf; - packet->Vcc = Vcc; - packet->Vservo = Vservo; - packet->flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE POWER_STATUS UNPACKING - - -/** - * @brief Get field Vcc from power_status message - * - * @return 5V rail voltage in millivolts - */ -static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field Vservo from power_status message - * - * @return servo rail voltage in millivolts - */ -static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field flags from power_status message - * - * @return power supply status flags (see MAV_POWER_STATUS enum) - */ -static inline uint16_t mavlink_msg_power_status_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Decode a power_status message into a struct - * - * @param msg The message to decode - * @param power_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_power_status_decode(const mavlink_message_t* msg, mavlink_power_status_t* power_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - power_status->Vcc = mavlink_msg_power_status_get_Vcc(msg); - power_status->Vservo = mavlink_msg_power_status_get_Vservo(msg); - power_status->flags = mavlink_msg_power_status_get_flags(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_POWER_STATUS_LEN? msg->len : MAVLINK_MSG_ID_POWER_STATUS_LEN; - memset(power_status, 0, MAVLINK_MSG_ID_POWER_STATUS_LEN); - memcpy(power_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_protocol_version.h b/include/mavlink/v2.0/common/mavlink_msg_protocol_version.h deleted file mode 100644 index 9cc80c2..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_protocol_version.h +++ /dev/null @@ -1,306 +0,0 @@ -#pragma once -// MESSAGE PROTOCOL_VERSION PACKING - -#define MAVLINK_MSG_ID_PROTOCOL_VERSION 300 - -MAVPACKED( -typedef struct __mavlink_protocol_version_t { - uint16_t version; /*< Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.*/ - uint16_t min_version; /*< Minimum MAVLink version supported*/ - uint16_t max_version; /*< Maximum MAVLink version supported (set to the same value as version by default)*/ - uint8_t spec_version_hash[8]; /*< The first 8 bytes (not characters printed in hex!) of the git hash.*/ - uint8_t library_version_hash[8]; /*< The first 8 bytes (not characters printed in hex!) of the git hash.*/ -}) mavlink_protocol_version_t; - -#define MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN 22 -#define MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN 22 -#define MAVLINK_MSG_ID_300_LEN 22 -#define MAVLINK_MSG_ID_300_MIN_LEN 22 - -#define MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC 217 -#define MAVLINK_MSG_ID_300_CRC 217 - -#define MAVLINK_MSG_PROTOCOL_VERSION_FIELD_SPEC_VERSION_HASH_LEN 8 -#define MAVLINK_MSG_PROTOCOL_VERSION_FIELD_LIBRARY_VERSION_HASH_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION { \ - 300, \ - "PROTOCOL_VERSION", \ - 5, \ - { { "version", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_protocol_version_t, version) }, \ - { "min_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_protocol_version_t, min_version) }, \ - { "max_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_protocol_version_t, max_version) }, \ - { "spec_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 6, offsetof(mavlink_protocol_version_t, spec_version_hash) }, \ - { "library_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 14, offsetof(mavlink_protocol_version_t, library_version_hash) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION { \ - "PROTOCOL_VERSION", \ - 5, \ - { { "version", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_protocol_version_t, version) }, \ - { "min_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_protocol_version_t, min_version) }, \ - { "max_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_protocol_version_t, max_version) }, \ - { "spec_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 6, offsetof(mavlink_protocol_version_t, spec_version_hash) }, \ - { "library_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 14, offsetof(mavlink_protocol_version_t, library_version_hash) }, \ - } \ -} -#endif - -/** - * @brief Pack a protocol_version 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 version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. - * @param min_version Minimum MAVLink version supported - * @param max_version Maximum MAVLink version supported (set to the same value as version by default) - * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_protocol_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t version, uint16_t min_version, uint16_t max_version, const uint8_t *spec_version_hash, const uint8_t *library_version_hash) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN]; - _mav_put_uint16_t(buf, 0, version); - _mav_put_uint16_t(buf, 2, min_version); - _mav_put_uint16_t(buf, 4, max_version); - _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8); - _mav_put_uint8_t_array(buf, 14, library_version_hash, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN); -#else - mavlink_protocol_version_t packet; - packet.version = version; - packet.min_version = min_version; - packet.max_version = max_version; - mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8); - mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PROTOCOL_VERSION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -} - -/** - * @brief Pack a protocol_version message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. - * @param min_version Minimum MAVLink version supported - * @param max_version Maximum MAVLink version supported (set to the same value as version by default) - * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_protocol_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t version,uint16_t min_version,uint16_t max_version,const uint8_t *spec_version_hash,const uint8_t *library_version_hash) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN]; - _mav_put_uint16_t(buf, 0, version); - _mav_put_uint16_t(buf, 2, min_version); - _mav_put_uint16_t(buf, 4, max_version); - _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8); - _mav_put_uint8_t_array(buf, 14, library_version_hash, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN); -#else - mavlink_protocol_version_t packet; - packet.version = version; - packet.min_version = min_version; - packet.max_version = max_version; - mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8); - mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PROTOCOL_VERSION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -} - -/** - * @brief Encode a protocol_version struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param protocol_version C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_protocol_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_protocol_version_t* protocol_version) -{ - return mavlink_msg_protocol_version_pack(system_id, component_id, msg, protocol_version->version, protocol_version->min_version, protocol_version->max_version, protocol_version->spec_version_hash, protocol_version->library_version_hash); -} - -/** - * @brief Encode a protocol_version struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param protocol_version C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_protocol_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_protocol_version_t* protocol_version) -{ - return mavlink_msg_protocol_version_pack_chan(system_id, component_id, chan, msg, protocol_version->version, protocol_version->min_version, protocol_version->max_version, protocol_version->spec_version_hash, protocol_version->library_version_hash); -} - -/** - * @brief Send a protocol_version message - * @param chan MAVLink channel to send the message - * - * @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. - * @param min_version Minimum MAVLink version supported - * @param max_version Maximum MAVLink version supported (set to the same value as version by default) - * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_protocol_version_send(mavlink_channel_t chan, uint16_t version, uint16_t min_version, uint16_t max_version, const uint8_t *spec_version_hash, const uint8_t *library_version_hash) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN]; - _mav_put_uint16_t(buf, 0, version); - _mav_put_uint16_t(buf, 2, min_version); - _mav_put_uint16_t(buf, 4, max_version); - _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8); - _mav_put_uint8_t_array(buf, 14, library_version_hash, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -#else - mavlink_protocol_version_t packet; - packet.version = version; - packet.min_version = min_version; - packet.max_version = max_version; - mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8); - mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, (const char *)&packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -#endif -} - -/** - * @brief Send a protocol_version message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_protocol_version_send_struct(mavlink_channel_t chan, const mavlink_protocol_version_t* protocol_version) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_protocol_version_send(chan, protocol_version->version, protocol_version->min_version, protocol_version->max_version, protocol_version->spec_version_hash, protocol_version->library_version_hash); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, (const char *)protocol_version, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_protocol_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t version, uint16_t min_version, uint16_t max_version, const uint8_t *spec_version_hash, const uint8_t *library_version_hash) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, version); - _mav_put_uint16_t(buf, 2, min_version); - _mav_put_uint16_t(buf, 4, max_version); - _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8); - _mav_put_uint8_t_array(buf, 14, library_version_hash, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -#else - mavlink_protocol_version_t *packet = (mavlink_protocol_version_t *)msgbuf; - packet->version = version; - packet->min_version = min_version; - packet->max_version = max_version; - mav_array_memcpy(packet->spec_version_hash, spec_version_hash, sizeof(uint8_t)*8); - mav_array_memcpy(packet->library_version_hash, library_version_hash, sizeof(uint8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, (const char *)packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PROTOCOL_VERSION UNPACKING - - -/** - * @brief Get field version from protocol_version message - * - * @return Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. - */ -static inline uint16_t mavlink_msg_protocol_version_get_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field min_version from protocol_version message - * - * @return Minimum MAVLink version supported - */ -static inline uint16_t mavlink_msg_protocol_version_get_min_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field max_version from protocol_version message - * - * @return Maximum MAVLink version supported (set to the same value as version by default) - */ -static inline uint16_t mavlink_msg_protocol_version_get_max_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field spec_version_hash from protocol_version message - * - * @return The first 8 bytes (not characters printed in hex!) of the git hash. - */ -static inline uint16_t mavlink_msg_protocol_version_get_spec_version_hash(const mavlink_message_t* msg, uint8_t *spec_version_hash) -{ - return _MAV_RETURN_uint8_t_array(msg, spec_version_hash, 8, 6); -} - -/** - * @brief Get field library_version_hash from protocol_version message - * - * @return The first 8 bytes (not characters printed in hex!) of the git hash. - */ -static inline uint16_t mavlink_msg_protocol_version_get_library_version_hash(const mavlink_message_t* msg, uint8_t *library_version_hash) -{ - return _MAV_RETURN_uint8_t_array(msg, library_version_hash, 8, 14); -} - -/** - * @brief Decode a protocol_version message into a struct - * - * @param msg The message to decode - * @param protocol_version C-struct to decode the message contents into - */ -static inline void mavlink_msg_protocol_version_decode(const mavlink_message_t* msg, mavlink_protocol_version_t* protocol_version) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - protocol_version->version = mavlink_msg_protocol_version_get_version(msg); - protocol_version->min_version = mavlink_msg_protocol_version_get_min_version(msg); - protocol_version->max_version = mavlink_msg_protocol_version_get_max_version(msg); - mavlink_msg_protocol_version_get_spec_version_hash(msg, protocol_version->spec_version_hash); - mavlink_msg_protocol_version_get_library_version_hash(msg, protocol_version->library_version_hash); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN? msg->len : MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN; - memset(protocol_version, 0, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN); - memcpy(protocol_version, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_radio_status.h b/include/mavlink/v2.0/common/mavlink_msg_radio_status.h deleted file mode 100644 index 8d266bb..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_radio_status.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE RADIO_STATUS PACKING - -#define MAVLINK_MSG_ID_RADIO_STATUS 109 - -MAVPACKED( -typedef struct __mavlink_radio_status_t { - uint16_t rxerrors; /*< Receive errors*/ - uint16_t fixed; /*< Count of error corrected packets*/ - uint8_t rssi; /*< Local signal strength*/ - uint8_t remrssi; /*< Remote signal strength*/ - uint8_t txbuf; /*< Remaining free buffer space in percent.*/ - uint8_t noise; /*< Background noise level*/ - uint8_t remnoise; /*< Remote background noise level*/ -}) mavlink_radio_status_t; - -#define MAVLINK_MSG_ID_RADIO_STATUS_LEN 9 -#define MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN 9 -#define MAVLINK_MSG_ID_109_LEN 9 -#define MAVLINK_MSG_ID_109_MIN_LEN 9 - -#define MAVLINK_MSG_ID_RADIO_STATUS_CRC 185 -#define MAVLINK_MSG_ID_109_CRC 185 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \ - 109, \ - "RADIO_STATUS", \ - 7, \ - { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ - { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ - { "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) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \ - "RADIO_STATUS", \ - 7, \ - { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ - { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ - { "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) }, \ - } \ -} -#endif - -/** - * @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 Remaining free buffer space in percent. - * @param noise Background noise level - * @param remnoise Remote background noise level - * @param rxerrors Receive errors - * @param fixed Count of error corrected packets - * @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; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -} - -/** - * @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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param rssi Local signal strength - * @param remrssi Remote signal strength - * @param txbuf Remaining free buffer space in percent. - * @param noise Background noise level - * @param remnoise Remote background noise level - * @param rxerrors Receive errors - * @param fixed Count of error corrected packets - * @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; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -} - -/** - * @brief Encode a radio_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param 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 Encode a radio_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param radio_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_radio_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status) -{ - return mavlink_msg_radio_status_pack_chan(system_id, component_id, chan, 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 Remaining free buffer space in percent. - * @param noise Background noise level - * @param remnoise Remote background noise level - * @param rxerrors Receive errors - * @param fixed Count of error corrected packets - */ -#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); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#endif -} - -/** - * @brief Send a radio_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_radio_status_send_struct(mavlink_channel_t chan, const mavlink_radio_status_t* radio_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_radio_status_send(chan, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)radio_status, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RADIO_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_radio_status_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#else - mavlink_radio_status_t *packet = (mavlink_radio_status_t *)msgbuf; - packet->rxerrors = rxerrors; - packet->fixed = fixed; - packet->rssi = rssi; - packet->remrssi = remrssi; - packet->txbuf = txbuf; - packet->noise = noise; - packet->remnoise = remnoise; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#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 Remaining free buffer space in percent. - */ -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 || !MAVLINK_ALIGNED_FIELDS - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_RADIO_STATUS_LEN? msg->len : MAVLINK_MSG_ID_RADIO_STATUS_LEN; - memset(radio_status, 0, MAVLINK_MSG_ID_RADIO_STATUS_LEN); - memcpy(radio_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_raw_imu.h b/include/mavlink/v2.0/common/mavlink_msg_raw_imu.h deleted file mode 100644 index 23833bc..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_raw_imu.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE RAW_IMU PACKING - -#define MAVLINK_MSG_ID_RAW_IMU 27 - -MAVPACKED( -typedef struct __mavlink_raw_imu_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int16_t xacc; /*< X acceleration (raw)*/ - int16_t yacc; /*< Y acceleration (raw)*/ - int16_t zacc; /*< Z acceleration (raw)*/ - int16_t xgyro; /*< Angular speed around X axis (raw)*/ - int16_t ygyro; /*< Angular speed around Y axis (raw)*/ - int16_t zgyro; /*< Angular speed around Z axis (raw)*/ - int16_t xmag; /*< X Magnetic field (raw)*/ - int16_t ymag; /*< Y Magnetic field (raw)*/ - int16_t zmag; /*< Z Magnetic field (raw)*/ -}) mavlink_raw_imu_t; - -#define MAVLINK_MSG_ID_RAW_IMU_LEN 26 -#define MAVLINK_MSG_ID_RAW_IMU_MIN_LEN 26 -#define MAVLINK_MSG_ID_27_LEN 26 -#define MAVLINK_MSG_ID_27_MIN_LEN 26 - -#define MAVLINK_MSG_ID_RAW_IMU_CRC 144 -#define MAVLINK_MSG_ID_27_CRC 144 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RAW_IMU { \ - 27, \ - "RAW_IMU", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RAW_IMU { \ - "RAW_IMU", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ - } \ -} -#endif - -/** - * @brief Pack a raw_imu 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 since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - 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; - - 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, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -} - -/** - * @brief Pack a raw_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - 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; - - 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, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -} - -/** - * @brief Encode a raw_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param raw_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) -{ - return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); -} - -/** - * @brief Encode a raw_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param raw_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) -{ - return mavlink_msg_raw_imu_pack_chan(system_id, component_id, chan, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); -} - -/** - * @brief Send a raw_imu message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _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, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#endif -} - -/** - * @brief Send a raw_imu message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_raw_imu_send_struct(mavlink_channel_t chan, const mavlink_raw_imu_t* raw_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_raw_imu_send(chan, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)raw_imu, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RAW_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, xacc); - _mav_put_int16_t(buf, 10, yacc); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _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, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - mavlink_raw_imu_t *packet = (mavlink_raw_imu_t *)msgbuf; - packet->time_usec = time_usec; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RAW_IMU UNPACKING - - -/** - * @brief Get field time_usec from raw_imu message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field xacc from raw_imu message - * - * @return X acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field yacc from raw_imu message - * - * @return Y acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field zacc from raw_imu message - * - * @return Z acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field xgyro from raw_imu message - * - * @return Angular speed around X axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field ygyro from raw_imu message - * - * @return Angular speed around Y axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field zgyro from raw_imu message - * - * @return Angular speed around Z axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field xmag from raw_imu message - * - * @return X Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field ymag from raw_imu message - * - * @return Y Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field zmag from raw_imu message - * - * @return Z Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 24); -} - -/** - * @brief Decode a raw_imu message into a struct - * - * @param msg The message to decode - * @param raw_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - raw_imu->time_usec = mavlink_msg_raw_imu_get_time_usec(msg); - raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg); - raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg); - raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg); - raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg); - raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg); - raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg); - raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg); - raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg); - raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_IMU_LEN? msg->len : MAVLINK_MSG_ID_RAW_IMU_LEN; - memset(raw_imu, 0, MAVLINK_MSG_ID_RAW_IMU_LEN); - memcpy(raw_imu, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_raw_pressure.h b/include/mavlink/v2.0/common/mavlink_msg_raw_pressure.h deleted file mode 100644 index 2d2ead9..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_raw_pressure.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE RAW_PRESSURE PACKING - -#define MAVLINK_MSG_ID_RAW_PRESSURE 28 - -MAVPACKED( -typedef struct __mavlink_raw_pressure_t { - uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ - int16_t press_abs; /*< Absolute pressure (raw)*/ - int16_t press_diff1; /*< Differential pressure 1 (raw, 0 if nonexistant)*/ - int16_t press_diff2; /*< Differential pressure 2 (raw, 0 if nonexistant)*/ - int16_t temperature; /*< Raw Temperature measurement (raw)*/ -}) mavlink_raw_pressure_t; - -#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 -#define MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN 16 -#define MAVLINK_MSG_ID_28_LEN 16 -#define MAVLINK_MSG_ID_28_MIN_LEN 16 - -#define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67 -#define MAVLINK_MSG_ID_28_CRC 67 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ - 28, \ - "RAW_PRESSURE", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \ - { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ - { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ - { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ - "RAW_PRESSURE", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \ - { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ - { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ - { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a raw_pressure 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 since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) - * @param temperature Raw Temperature measurement (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - - 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, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -} - -/** - * @brief Pack a raw_pressure message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) - * @param temperature Raw Temperature measurement (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - - 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, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -} - -/** - * @brief Encode a raw_pressure struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param raw_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) -{ - return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); -} - -/** - * @brief Encode a raw_pressure struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param raw_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) -{ - return mavlink_msg_raw_pressure_pack_chan(system_id, component_id, chan, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); -} - -/** - * @brief Send a raw_pressure message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) - * @param temperature Raw Temperature measurement (raw) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#endif -} - -/** - * @brief Send a raw_pressure message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_raw_pressure_send_struct(mavlink_channel_t chan, const mavlink_raw_pressure_t* raw_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_raw_pressure_send(chan, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)raw_pressure, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_raw_pressure_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - mavlink_raw_pressure_t *packet = (mavlink_raw_pressure_t *)msgbuf; - packet->time_usec = time_usec; - packet->press_abs = press_abs; - packet->press_diff1 = press_diff1; - packet->press_diff2 = press_diff2; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RAW_PRESSURE UNPACKING - - -/** - * @brief Get field time_usec from raw_pressure message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field press_abs from raw_pressure message - * - * @return Absolute pressure (raw) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field press_diff1 from raw_pressure message - * - * @return Differential pressure 1 (raw, 0 if nonexistant) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field press_diff2 from raw_pressure message - * - * @return Differential pressure 2 (raw, 0 if nonexistant) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field temperature from raw_pressure message - * - * @return Raw Temperature measurement (raw) - */ -static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Decode a raw_pressure message into a struct - * - * @param msg The message to decode - * @param raw_pressure C-struct to decode the message contents into - */ -static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg); - raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg); - raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg); - raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg); - raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_PRESSURE_LEN? msg->len : MAVLINK_MSG_ID_RAW_PRESSURE_LEN; - memset(raw_pressure, 0, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); - memcpy(raw_pressure, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_rc_channels.h b/include/mavlink/v2.0/common/mavlink_msg_rc_channels.h deleted file mode 100644 index f763737..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_rc_channels.h +++ /dev/null @@ -1,713 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS 65 - -MAVPACKED( -typedef struct __mavlink_rc_channels_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan9_raw; /*< RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan10_raw; /*< RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan11_raw; /*< RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan12_raw; /*< RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan13_raw; /*< RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan14_raw; /*< RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan15_raw; /*< RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan16_raw; /*< RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan17_raw; /*< RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan18_raw; /*< RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint8_t chancount; /*< Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ -}) mavlink_rc_channels_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_LEN 42 -#define MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN 42 -#define MAVLINK_MSG_ID_65_LEN 42 -#define MAVLINK_MSG_ID_65_MIN_LEN 42 - -#define MAVLINK_MSG_ID_RC_CHANNELS_CRC 118 -#define MAVLINK_MSG_ID_65_CRC 118 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \ - 65, \ - "RC_CHANNELS", \ - 21, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \ - { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \ - { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \ - { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \ - { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \ - { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \ - { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \ - { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \ - "RC_CHANNELS", \ - 21, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \ - { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \ - { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \ - { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \ - { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \ - { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \ - { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \ - { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels 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_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -} - -/** - * @brief Pack a rc_channels message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t chancount,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,uint16_t chan13_raw,uint16_t chan14_raw,uint16_t chan15_raw,uint16_t chan16_raw,uint16_t chan17_raw,uint16_t chan18_raw,uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -} - -/** - * @brief Encode a rc_channels struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) -{ - return mavlink_msg_rc_channels_pack(system_id, component_id, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); -} - -/** - * @brief Encode a rc_channels struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) -{ - return mavlink_msg_rc_channels_pack_chan(system_id, component_id, chan, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); -} - -/** - * @brief Send a rc_channels message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rc_channels_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#endif -} - -/** - * @brief Send a rc_channels message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_t* rc_channels) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_send(chan, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)rc_channels, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - mavlink_rc_channels_t *packet = (mavlink_rc_channels_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->chan9_raw = chan9_raw; - packet->chan10_raw = chan10_raw; - packet->chan11_raw = chan11_raw; - packet->chan12_raw = chan12_raw; - packet->chan13_raw = chan13_raw; - packet->chan14_raw = chan14_raw; - packet->chan15_raw = chan15_raw; - packet->chan16_raw = chan16_raw; - packet->chan17_raw = chan17_raw; - packet->chan18_raw = chan18_raw; - packet->chancount = chancount; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field chancount from rc_channels message - * - * @return Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - */ -static inline uint8_t mavlink_msg_rc_channels_get_chancount(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field chan1_raw from rc_channels message - * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan2_raw from rc_channels message - * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan3_raw from rc_channels message - * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan4_raw from rc_channels message - * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan5_raw from rc_channels message - * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan6_raw from rc_channels message - * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan7_raw from rc_channels message - * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan8_raw from rc_channels message - * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field chan9_raw from rc_channels message - * - * @return RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field chan10_raw from rc_channels message - * - * @return RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field chan11_raw from rc_channels message - * - * @return RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field chan12_raw from rc_channels message - * - * @return RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field chan13_raw from rc_channels message - * - * @return RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field chan14_raw from rc_channels message - * - * @return RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field chan15_raw from rc_channels message - * - * @return RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field chan16_raw from rc_channels message - * - * @return RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 34); -} - -/** - * @brief Get field chan17_raw from rc_channels message - * - * @return RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 36); -} - -/** - * @brief Get field chan18_raw from rc_channels message - * - * @return RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 38); -} - -/** - * @brief Get field rssi from rc_channels message - * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Decode a rc_channels message into a struct - * - * @param msg The message to decode - * @param rc_channels C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_decode(const mavlink_message_t* msg, mavlink_rc_channels_t* rc_channels) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels->time_boot_ms = mavlink_msg_rc_channels_get_time_boot_ms(msg); - rc_channels->chan1_raw = mavlink_msg_rc_channels_get_chan1_raw(msg); - rc_channels->chan2_raw = mavlink_msg_rc_channels_get_chan2_raw(msg); - rc_channels->chan3_raw = mavlink_msg_rc_channels_get_chan3_raw(msg); - rc_channels->chan4_raw = mavlink_msg_rc_channels_get_chan4_raw(msg); - rc_channels->chan5_raw = mavlink_msg_rc_channels_get_chan5_raw(msg); - rc_channels->chan6_raw = mavlink_msg_rc_channels_get_chan6_raw(msg); - rc_channels->chan7_raw = mavlink_msg_rc_channels_get_chan7_raw(msg); - rc_channels->chan8_raw = mavlink_msg_rc_channels_get_chan8_raw(msg); - rc_channels->chan9_raw = mavlink_msg_rc_channels_get_chan9_raw(msg); - rc_channels->chan10_raw = mavlink_msg_rc_channels_get_chan10_raw(msg); - rc_channels->chan11_raw = mavlink_msg_rc_channels_get_chan11_raw(msg); - rc_channels->chan12_raw = mavlink_msg_rc_channels_get_chan12_raw(msg); - rc_channels->chan13_raw = mavlink_msg_rc_channels_get_chan13_raw(msg); - rc_channels->chan14_raw = mavlink_msg_rc_channels_get_chan14_raw(msg); - rc_channels->chan15_raw = mavlink_msg_rc_channels_get_chan15_raw(msg); - rc_channels->chan16_raw = mavlink_msg_rc_channels_get_chan16_raw(msg); - rc_channels->chan17_raw = mavlink_msg_rc_channels_get_chan17_raw(msg); - rc_channels->chan18_raw = mavlink_msg_rc_channels_get_chan18_raw(msg); - rc_channels->chancount = mavlink_msg_rc_channels_get_chancount(msg); - rc_channels->rssi = mavlink_msg_rc_channels_get_rssi(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_LEN; - memset(rc_channels, 0, MAVLINK_MSG_ID_RC_CHANNELS_LEN); - memcpy(rc_channels, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_rc_channels_override.h b/include/mavlink/v2.0/common/mavlink_msg_rc_channels_override.h deleted file mode 100644 index 970e926..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_rc_channels_override.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS_OVERRIDE PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 - -MAVPACKED( -typedef struct __mavlink_rc_channels_override_t { - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_rc_channels_override_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN 18 -#define MAVLINK_MSG_ID_70_LEN 18 -#define MAVLINK_MSG_ID_70_MIN_LEN 18 - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124 -#define MAVLINK_MSG_ID_70_CRC 124 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ - 70, \ - "RC_CHANNELS_OVERRIDE", \ - 10, \ - { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ - "RC_CHANNELS_OVERRIDE", \ - 10, \ - { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels_override message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - 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; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -} - -/** - * @brief Pack a rc_channels_override message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - 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; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.target_system = target_system; - packet.target_component = target_component; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -} - -/** - * @brief Encode a rc_channels_override struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_override C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) -{ - return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); -} - -/** - * @brief Encode a rc_channels_override struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_override C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_override_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) -{ - return mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, chan, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); -} - -/** - * @brief Send a rc_channels_override message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - mavlink_rc_channels_override_t packet; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - 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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#endif -} - -/** - * @brief Send a rc_channels_override message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_override_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_override_t* rc_channels_override) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_override_send(chan, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)rc_channels_override, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_override_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, chan1_raw); - _mav_put_uint16_t(buf, 2, chan2_raw); - _mav_put_uint16_t(buf, 4, chan3_raw); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - mavlink_rc_channels_override_t *packet = (mavlink_rc_channels_override_t *)msgbuf; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - 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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING - - -/** - * @brief Get field target_system from rc_channels_override message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field target_component from rc_channels_override message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field chan1_raw from rc_channels_override message - * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field chan2_raw from rc_channels_override message - * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field chan3_raw from rc_channels_override message - * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan4_raw from rc_channels_override message - * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan5_raw from rc_channels_override message - * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan6_raw from rc_channels_override message - * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan7_raw from rc_channels_override message - * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan8_raw from rc_channels_override message - * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Decode a rc_channels_override message into a struct - * - * @param msg The message to decode - * @param rc_channels_override C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg); - rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg); - rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg); - rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg); - rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg); - rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg); - rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg); - rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN; - memset(rc_channels_override, 0, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); - memcpy(rc_channels_override, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_rc_channels_raw.h b/include/mavlink/v2.0/common/mavlink_msg_rc_channels_raw.h deleted file mode 100644 index 87d1b4a..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_rc_channels_raw.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS_RAW PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 - -MAVPACKED( -typedef struct __mavlink_rc_channels_raw_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ -}) mavlink_rc_channels_raw_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN 22 -#define MAVLINK_MSG_ID_35_LEN 22 -#define MAVLINK_MSG_ID_35_MIN_LEN 22 - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244 -#define MAVLINK_MSG_ID_35_CRC 244 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ - 35, \ - "RC_CHANNELS_RAW", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ - "RC_CHANNELS_RAW", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels_raw 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_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - 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; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -} - -/** - * @brief Pack a rc_channels_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - 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; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -} - -/** - * @brief Encode a rc_channels_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) -{ - return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); -} - -/** - * @brief Encode a rc_channels_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) -{ - return mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, chan, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); -} - -/** - * @brief Send a rc_channels_raw message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - mavlink_rc_channels_raw_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#endif -} - -/** - * @brief Send a rc_channels_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_raw_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_raw_t* rc_channels_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_raw_send(chan, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)rc_channels_raw, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_raw_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - mavlink_rc_channels_raw_t *packet = (mavlink_rc_channels_raw_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->port = port; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_RAW UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels_raw message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from rc_channels_raw message - * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - */ -static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field chan1_raw from rc_channels_raw message - * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan2_raw from rc_channels_raw message - * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan3_raw from rc_channels_raw message - * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan4_raw from rc_channels_raw message - * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan5_raw from rc_channels_raw message - * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan6_raw from rc_channels_raw message - * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan7_raw from rc_channels_raw message - * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan8_raw from rc_channels_raw message - * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field rssi from rc_channels_raw message - * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a rc_channels_raw message into a struct - * - * @param msg The message to decode - * @param rc_channels_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels_raw->time_boot_ms = mavlink_msg_rc_channels_raw_get_time_boot_ms(msg); - rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg); - rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg); - rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg); - rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg); - rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg); - rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg); - rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg); - rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN; - memset(rc_channels_raw, 0, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); - memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_rc_channels_scaled.h b/include/mavlink/v2.0/common/mavlink_msg_rc_channels_scaled.h deleted file mode 100644 index 5b04333..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_rc_channels_scaled.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS_SCALED PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34 - -MAVPACKED( -typedef struct __mavlink_rc_channels_scaled_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t chan1_scaled; /*< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan2_scaled; /*< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan3_scaled; /*< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan4_scaled; /*< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan5_scaled; /*< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan6_scaled; /*< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan7_scaled; /*< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - int16_t chan8_scaled; /*< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.*/ - uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ -}) mavlink_rc_channels_scaled_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN 22 -#define MAVLINK_MSG_ID_34_LEN 22 -#define MAVLINK_MSG_ID_34_MIN_LEN 22 - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237 -#define MAVLINK_MSG_ID_34_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ - 34, \ - "RC_CHANNELS_SCALED", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ - { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ - { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ - { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ - { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ - { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ - { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ - { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ - { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ - "RC_CHANNELS_SCALED", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ - { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ - { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ - { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ - { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ - { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ - { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ - { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ - { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels_scaled 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_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - 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; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -} - -/** - * @brief Pack a rc_channels_scaled message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - 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; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - - 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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -} - -/** - * @brief Encode a rc_channels_scaled struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_scaled C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ - return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); -} - -/** - * @brief Encode a rc_channels_scaled struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_scaled C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ - return mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, chan, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); -} - -/** - * @brief Send a rc_channels_scaled message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - mavlink_rc_channels_scaled_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#endif -} - -/** - * @brief Send a rc_channels_scaled message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_scaled_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_scaled_send(chan, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)rc_channels_scaled, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_scaled_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - mavlink_rc_channels_scaled_t *packet = (mavlink_rc_channels_scaled_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_scaled = chan1_scaled; - packet->chan2_scaled = chan2_scaled; - packet->chan3_scaled = chan3_scaled; - packet->chan4_scaled = chan4_scaled; - packet->chan5_scaled = chan5_scaled; - packet->chan6_scaled = chan6_scaled; - packet->chan7_scaled = chan7_scaled; - packet->chan8_scaled = chan8_scaled; - packet->port = port; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_SCALED UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels_scaled message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from rc_channels_scaled message - * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - */ -static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field chan1_scaled from rc_channels_scaled message - * - * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field chan2_scaled from rc_channels_scaled message - * - * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field chan3_scaled from rc_channels_scaled message - * - * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field chan4_scaled from rc_channels_scaled message - * - * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field chan5_scaled from rc_channels_scaled message - * - * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field chan6_scaled from rc_channels_scaled message - * - * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field chan7_scaled from rc_channels_scaled message - * - * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field chan8_scaled from rc_channels_scaled message - * - * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field rssi from rc_channels_scaled message - * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a rc_channels_scaled message into a struct - * - * @param msg The message to decode - * @param rc_channels_scaled C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels_scaled->time_boot_ms = mavlink_msg_rc_channels_scaled_get_time_boot_ms(msg); - rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg); - rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg); - rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg); - rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg); - rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg); - rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg); - rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg); - rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN; - memset(rc_channels_scaled, 0, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); - memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_request_data_stream.h b/include/mavlink/v2.0/common/mavlink_msg_request_data_stream.h deleted file mode 100644 index 047c2c3..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_request_data_stream.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE REQUEST_DATA_STREAM PACKING - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 - -MAVPACKED( -typedef struct __mavlink_request_data_stream_t { - uint16_t req_message_rate; /*< The requested message rate*/ - uint8_t target_system; /*< The target requested to send the message stream.*/ - uint8_t target_component; /*< The target requested to send the message stream.*/ - uint8_t req_stream_id; /*< The ID of the requested data stream*/ - uint8_t start_stop; /*< 1 to start sending, 0 to stop sending.*/ -}) mavlink_request_data_stream_t; - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN 6 -#define MAVLINK_MSG_ID_66_LEN 6 -#define MAVLINK_MSG_ID_66_MIN_LEN 6 - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148 -#define MAVLINK_MSG_ID_66_CRC 148 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ - 66, \ - "REQUEST_DATA_STREAM", \ - 5, \ - { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ - { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ - { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ - "REQUEST_DATA_STREAM", \ - 5, \ - { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ - { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ - { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ - } \ -} -#endif - -/** - * @brief Pack a request_data_stream message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.req_stream_id = req_stream_id; - packet.start_stop = start_stop; - - 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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -} - -/** - * @brief Pack a request_data_stream message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.req_stream_id = req_stream_id; - packet.start_stop = start_stop; - - 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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -} - -/** - * @brief Encode a request_data_stream struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param request_data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) -{ - return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); -} - -/** - * @brief Encode a request_data_stream struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param request_data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_request_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) -{ - return mavlink_msg_request_data_stream_pack_chan(system_id, component_id, chan, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); -} - -/** - * @brief Send a request_data_stream message - * @param chan MAVLink channel to send the message - * - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - 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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#endif -} - -/** - * @brief Send a request_data_stream message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_request_data_stream_send_struct(mavlink_channel_t chan, const mavlink_request_data_stream_t* request_data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_request_data_stream_send(chan, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)request_data_stream, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#endif -} - -#if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_request_data_stream_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - mavlink_request_data_stream_t *packet = (mavlink_request_data_stream_t *)msgbuf; - packet->req_message_rate = req_message_rate; - packet->target_system = target_system; - packet->target_component = target_component; - 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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#endif -} -#endif - -#endif - -// MESSAGE REQUEST_DATA_STREAM UNPACKING - - -/** - * @brief Get field target_system from request_data_stream message - * - * @return The target requested to send the message stream. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from request_data_stream message - * - * @return The target requested to send the message stream. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field req_stream_id from request_data_stream message - * - * @return The ID of the requested data stream - */ -static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field req_message_rate from request_data_stream message - * - * @return The requested message rate - */ -static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field start_stop from request_data_stream message - * - * @return 1 to start sending, 0 to stop sending. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Decode a request_data_stream message into a struct - * - * @param msg The message to decode - * @param request_data_stream C-struct to decode the message contents into - */ -static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg); - request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg); - request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN? msg->len : MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN; - memset(request_data_stream, 0, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); - memcpy(request_data_stream, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_resource_request.h b/include/mavlink/v2.0/common/mavlink_msg_resource_request.h deleted file mode 100644 index 69a1177..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_resource_request.h +++ /dev/null @@ -1,306 +0,0 @@ -#pragma once -// MESSAGE RESOURCE_REQUEST PACKING - -#define MAVLINK_MSG_ID_RESOURCE_REQUEST 142 - -MAVPACKED( -typedef struct __mavlink_resource_request_t { - uint8_t request_id; /*< Request ID. This ID should be re-used when sending back URI contents*/ - uint8_t uri_type; /*< The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary*/ - uint8_t uri[120]; /*< The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)*/ - uint8_t transfer_type; /*< The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.*/ - uint8_t storage[120]; /*< The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).*/ -}) mavlink_resource_request_t; - -#define MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN 243 -#define MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN 243 -#define MAVLINK_MSG_ID_142_LEN 243 -#define MAVLINK_MSG_ID_142_MIN_LEN 243 - -#define MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC 72 -#define MAVLINK_MSG_ID_142_CRC 72 - -#define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_URI_LEN 120 -#define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_STORAGE_LEN 120 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST { \ - 142, \ - "RESOURCE_REQUEST", \ - 5, \ - { { "request_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_resource_request_t, request_id) }, \ - { "uri_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_resource_request_t, uri_type) }, \ - { "uri", NULL, MAVLINK_TYPE_UINT8_T, 120, 2, offsetof(mavlink_resource_request_t, uri) }, \ - { "transfer_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 122, offsetof(mavlink_resource_request_t, transfer_type) }, \ - { "storage", NULL, MAVLINK_TYPE_UINT8_T, 120, 123, offsetof(mavlink_resource_request_t, storage) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST { \ - "RESOURCE_REQUEST", \ - 5, \ - { { "request_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_resource_request_t, request_id) }, \ - { "uri_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_resource_request_t, uri_type) }, \ - { "uri", NULL, MAVLINK_TYPE_UINT8_T, 120, 2, offsetof(mavlink_resource_request_t, uri) }, \ - { "transfer_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 122, offsetof(mavlink_resource_request_t, transfer_type) }, \ - { "storage", NULL, MAVLINK_TYPE_UINT8_T, 120, 123, offsetof(mavlink_resource_request_t, storage) }, \ - } \ -} -#endif - -/** - * @brief Pack a resource_request 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 request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_resource_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#else - mavlink_resource_request_t packet; - packet.request_id = request_id; - packet.uri_type = uri_type; - packet.transfer_type = transfer_type; - mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -} - -/** - * @brief Pack a resource_request message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_resource_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t request_id,uint8_t uri_type,const uint8_t *uri,uint8_t transfer_type,const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#else - mavlink_resource_request_t packet; - packet.request_id = request_id; - packet.uri_type = uri_type; - packet.transfer_type = transfer_type; - mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -} - -/** - * @brief Encode a resource_request struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param resource_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_resource_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request) -{ - return mavlink_msg_resource_request_pack(system_id, component_id, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); -} - -/** - * @brief Encode a resource_request struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param resource_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_resource_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request) -{ - return mavlink_msg_resource_request_pack_chan(system_id, component_id, chan, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); -} - -/** - * @brief Send a resource_request message - * @param chan MAVLink channel to send the message - * - * @param request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_resource_request_send(mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#else - mavlink_resource_request_t packet; - packet.request_id = request_id; - packet.uri_type = uri_type; - packet.transfer_type = transfer_type; - mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#endif -} - -/** - * @brief Send a resource_request message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_resource_request_send_struct(mavlink_channel_t chan, const mavlink_resource_request_t* resource_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_resource_request_send(chan, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)resource_request, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_resource_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#else - mavlink_resource_request_t *packet = (mavlink_resource_request_t *)msgbuf; - packet->request_id = request_id; - packet->uri_type = uri_type; - packet->transfer_type = transfer_type; - mav_array_memcpy(packet->uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet->storage, storage, sizeof(uint8_t)*120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RESOURCE_REQUEST UNPACKING - - -/** - * @brief Get field request_id from resource_request message - * - * @return Request ID. This ID should be re-used when sending back URI contents - */ -static inline uint8_t mavlink_msg_resource_request_get_request_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field uri_type from resource_request message - * - * @return The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - */ -static inline uint8_t mavlink_msg_resource_request_get_uri_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field uri from resource_request message - * - * @return The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - */ -static inline uint16_t mavlink_msg_resource_request_get_uri(const mavlink_message_t* msg, uint8_t *uri) -{ - return _MAV_RETURN_uint8_t_array(msg, uri, 120, 2); -} - -/** - * @brief Get field transfer_type from resource_request message - * - * @return The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - */ -static inline uint8_t mavlink_msg_resource_request_get_transfer_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 122); -} - -/** - * @brief Get field storage from resource_request message - * - * @return The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - */ -static inline uint16_t mavlink_msg_resource_request_get_storage(const mavlink_message_t* msg, uint8_t *storage) -{ - return _MAV_RETURN_uint8_t_array(msg, storage, 120, 123); -} - -/** - * @brief Decode a resource_request message into a struct - * - * @param msg The message to decode - * @param resource_request C-struct to decode the message contents into - */ -static inline void mavlink_msg_resource_request_decode(const mavlink_message_t* msg, mavlink_resource_request_t* resource_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - resource_request->request_id = mavlink_msg_resource_request_get_request_id(msg); - resource_request->uri_type = mavlink_msg_resource_request_get_uri_type(msg); - mavlink_msg_resource_request_get_uri(msg, resource_request->uri); - resource_request->transfer_type = mavlink_msg_resource_request_get_transfer_type(msg); - mavlink_msg_resource_request_get_storage(msg, resource_request->storage); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN; - memset(resource_request, 0, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); - memcpy(resource_request, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_safety_allowed_area.h b/include/mavlink/v2.0/common/mavlink_msg_safety_allowed_area.h deleted file mode 100644 index cad1c19..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_safety_allowed_area.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE SAFETY_ALLOWED_AREA PACKING - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 - -MAVPACKED( -typedef struct __mavlink_safety_allowed_area_t { - float p1x; /*< x position 1 / Latitude 1*/ - float p1y; /*< y position 1 / Longitude 1*/ - float p1z; /*< z position 1 / Altitude 1*/ - float p2x; /*< x position 2 / Latitude 2*/ - float p2y; /*< y position 2 / Longitude 2*/ - float p2z; /*< z position 2 / Altitude 2*/ - uint8_t frame; /*< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ -}) mavlink_safety_allowed_area_t; - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN 25 -#define MAVLINK_MSG_ID_55_LEN 25 -#define MAVLINK_MSG_ID_55_MIN_LEN 25 - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3 -#define MAVLINK_MSG_ID_55_CRC 3 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ - 55, \ - "SAFETY_ALLOWED_AREA", \ - 7, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ - "SAFETY_ALLOWED_AREA", \ - 7, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a safety_allowed_area 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 frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - - 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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -} - -/** - * @brief Pack a safety_allowed_area message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - - 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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -} - -/** - * @brief Encode a safety_allowed_area struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param safety_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) -{ - return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); -} - -/** - * @brief Encode a safety_allowed_area struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param safety_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) -{ - return mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); -} - -/** - * @brief Send a safety_allowed_area message - * @param chan MAVLink channel to send the message - * - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#endif -} - -/** - * @brief Send a safety_allowed_area message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_safety_allowed_area_send_struct(mavlink_channel_t chan, const mavlink_safety_allowed_area_t* safety_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_safety_allowed_area_send(chan, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)safety_allowed_area, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_safety_allowed_area_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - mavlink_safety_allowed_area_t *packet = (mavlink_safety_allowed_area_t *)msgbuf; - packet->p1x = p1x; - packet->p1y = p1y; - packet->p1z = p1z; - packet->p2x = p2x; - packet->p2y = p2y; - packet->p2z = p2z; - packet->frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SAFETY_ALLOWED_AREA UNPACKING - - -/** - * @brief Get field frame from safety_allowed_area message - * - * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - */ -static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field p1x from safety_allowed_area message - * - * @return x position 1 / Latitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field p1y from safety_allowed_area message - * - * @return y position 1 / Longitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field p1z from safety_allowed_area message - * - * @return z position 1 / Altitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field p2x from safety_allowed_area message - * - * @return x position 2 / Latitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field p2y from safety_allowed_area message - * - * @return y position 2 / Longitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field p2z from safety_allowed_area message - * - * @return z position 2 / Altitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a safety_allowed_area message into a struct - * - * @param msg The message to decode - * @param safety_allowed_area C-struct to decode the message contents into - */ -static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg); - safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg); - safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg); - safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg); - safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN? msg->len : MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN; - memset(safety_allowed_area, 0, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); - memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_safety_set_allowed_area.h b/include/mavlink/v2.0/common/mavlink_msg_safety_set_allowed_area.h deleted file mode 100644 index 293c1f0..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_safety_set_allowed_area.h +++ /dev/null @@ -1,413 +0,0 @@ -#pragma once -// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 - -MAVPACKED( -typedef struct __mavlink_safety_set_allowed_area_t { - float p1x; /*< x position 1 / Latitude 1*/ - float p1y; /*< y position 1 / Longitude 1*/ - float p1z; /*< z position 1 / Altitude 1*/ - float p2x; /*< x position 2 / Latitude 2*/ - float p2y; /*< y position 2 / Longitude 2*/ - float p2z; /*< z position 2 / Altitude 2*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ -}) mavlink_safety_set_allowed_area_t; - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN 27 -#define MAVLINK_MSG_ID_54_LEN 27 -#define MAVLINK_MSG_ID_54_MIN_LEN 27 - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15 -#define MAVLINK_MSG_ID_54_CRC 15 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ - 54, \ - "SAFETY_SET_ALLOWED_AREA", \ - 9, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ - "SAFETY_SET_ALLOWED_AREA", \ - 9, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a safety_set_allowed_area message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - - 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; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - - 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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -} - -/** - * @brief Pack a safety_set_allowed_area message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - - 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; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - - 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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -} - -/** - * @brief Encode a safety_set_allowed_area struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param safety_set_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ - return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); -} - -/** - * @brief Encode a safety_set_allowed_area struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param safety_set_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ - return mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); -} - -/** - * @brief Send a safety_set_allowed_area message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - mavlink_safety_set_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#endif -} - -/** - * @brief Send a safety_set_allowed_area message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_safety_set_allowed_area_send_struct(mavlink_channel_t chan, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_safety_set_allowed_area_send(chan, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)safety_set_allowed_area, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_safety_set_allowed_area_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - mavlink_safety_set_allowed_area_t *packet = (mavlink_safety_set_allowed_area_t *)msgbuf; - packet->p1x = p1x; - packet->p1y = p1y; - packet->p1z = p1z; - packet->p2x = p2x; - packet->p2y = p2y; - packet->p2z = p2z; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING - - -/** - * @brief Get field target_system from safety_set_allowed_area message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field target_component from safety_set_allowed_area message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field frame from safety_set_allowed_area message - * - * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field p1x from safety_set_allowed_area message - * - * @return x position 1 / Latitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field p1y from safety_set_allowed_area message - * - * @return y position 1 / Longitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field p1z from safety_set_allowed_area message - * - * @return z position 1 / Altitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field p2x from safety_set_allowed_area message - * - * @return x position 2 / Latitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field p2y from safety_set_allowed_area message - * - * @return y position 2 / Longitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field p2z from safety_set_allowed_area message - * - * @return z position 2 / Altitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a safety_set_allowed_area message into a struct - * - * @param msg The message to decode - * @param safety_set_allowed_area C-struct to decode the message contents into - */ -static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg); - safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg); - safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg); - safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg); - safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg); - safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg); - safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN? msg->len : MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN; - memset(safety_set_allowed_area, 0, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); - memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_scaled_imu.h b/include/mavlink/v2.0/common/mavlink_msg_scaled_imu.h deleted file mode 100644 index 2994d99..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_scaled_imu.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE SCALED_IMU PACKING - -#define MAVLINK_MSG_ID_SCALED_IMU 26 - -MAVPACKED( -typedef struct __mavlink_scaled_imu_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ - int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ - int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ - int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ - int16_t xmag; /*< X Magnetic field (milli tesla)*/ - int16_t ymag; /*< Y Magnetic field (milli tesla)*/ - int16_t zmag; /*< Z Magnetic field (milli tesla)*/ -}) mavlink_scaled_imu_t; - -#define MAVLINK_MSG_ID_SCALED_IMU_LEN 22 -#define MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN 22 -#define MAVLINK_MSG_ID_26_LEN 22 -#define MAVLINK_MSG_ID_26_MIN_LEN 22 - -#define MAVLINK_MSG_ID_SCALED_IMU_CRC 170 -#define MAVLINK_MSG_ID_26_CRC 170 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ - 26, \ - "SCALED_IMU", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ - "SCALED_IMU", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_imu 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_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - 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; - 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; - - 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, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -} - -/** - * @brief Pack a scaled_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - 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; - 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; - - 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, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -} - -/** - * @brief Encode a scaled_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) -{ - return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); -} - -/** - * @brief Encode a scaled_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) -{ - return mavlink_msg_scaled_imu_pack_chan(system_id, component_id, chan, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); -} - -/** - * @brief Send a scaled_imu message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _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, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - mavlink_scaled_imu_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#endif -} - -/** - * @brief Send a scaled_imu message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_imu_send_struct(mavlink_channel_t chan, const mavlink_scaled_imu_t* scaled_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_imu_send(chan, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)scaled_imu, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_imu_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _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, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - mavlink_scaled_imu_t *packet = (mavlink_scaled_imu_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_IMU UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_imu message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field xacc from scaled_imu message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field yacc from scaled_imu message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field zacc from scaled_imu message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field xgyro from scaled_imu message - * - * @return Angular speed around X axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field ygyro from scaled_imu message - * - * @return Angular speed around Y axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field zgyro from scaled_imu message - * - * @return Angular speed around Z axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field xmag from scaled_imu message - * - * @return X Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field ymag from scaled_imu message - * - * @return Y Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field zmag from scaled_imu message - * - * @return Z Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Decode a scaled_imu message into a struct - * - * @param msg The message to decode - * @param scaled_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_imu->time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg); - scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg); - scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg); - scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg); - scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg); - scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg); - scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg); - scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg); - scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg); - scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_IMU_LEN? msg->len : MAVLINK_MSG_ID_SCALED_IMU_LEN; - memset(scaled_imu, 0, MAVLINK_MSG_ID_SCALED_IMU_LEN); - memcpy(scaled_imu, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_scaled_imu2.h b/include/mavlink/v2.0/common/mavlink_msg_scaled_imu2.h deleted file mode 100644 index c232691..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_scaled_imu2.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE SCALED_IMU2 PACKING - -#define MAVLINK_MSG_ID_SCALED_IMU2 116 - -MAVPACKED( -typedef struct __mavlink_scaled_imu2_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ - int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ - int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ - int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ - int16_t xmag; /*< X Magnetic field (milli tesla)*/ - int16_t ymag; /*< Y Magnetic field (milli tesla)*/ - int16_t zmag; /*< Z Magnetic field (milli tesla)*/ -}) mavlink_scaled_imu2_t; - -#define MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 -#define MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN 22 -#define MAVLINK_MSG_ID_116_LEN 22 -#define MAVLINK_MSG_ID_116_MIN_LEN 22 - -#define MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 -#define MAVLINK_MSG_ID_116_CRC 76 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \ - 116, \ - "SCALED_IMU2", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \ - "SCALED_IMU2", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_imu2 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_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -} - -/** - * @brief Pack a scaled_imu2 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -} - -/** - * @brief Encode a scaled_imu2 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_imu2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) -{ - return mavlink_msg_scaled_imu2_pack(system_id, component_id, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); -} - -/** - * @brief Encode a scaled_imu2 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_imu2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) -{ - return mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, chan, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); -} - -/** - * @brief Send a scaled_imu2 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_imu2_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[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#endif -} - -/** - * @brief Send a scaled_imu2 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_imu2_send_struct(mavlink_channel_t chan, const mavlink_scaled_imu2_t* scaled_imu2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_imu2_send(chan, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)scaled_imu2, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_IMU2_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_imu2_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - mavlink_scaled_imu2_t *packet = (mavlink_scaled_imu2_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_IMU2 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_imu2 message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field xacc from scaled_imu2 message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field yacc from scaled_imu2 message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field zacc from scaled_imu2 message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field xgyro from scaled_imu2 message - * - * @return Angular speed around X axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field ygyro from scaled_imu2 message - * - * @return Angular speed around Y axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field zgyro from scaled_imu2 message - * - * @return Angular speed around Z axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field xmag from scaled_imu2 message - * - * @return X Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field ymag from scaled_imu2 message - * - * @return Y Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field zmag from scaled_imu2 message - * - * @return Z Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Decode a scaled_imu2 message into a struct - * - * @param msg The message to decode - * @param scaled_imu2 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_imu2_decode(const mavlink_message_t* msg, mavlink_scaled_imu2_t* scaled_imu2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_imu2->time_boot_ms = mavlink_msg_scaled_imu2_get_time_boot_ms(msg); - scaled_imu2->xacc = mavlink_msg_scaled_imu2_get_xacc(msg); - scaled_imu2->yacc = mavlink_msg_scaled_imu2_get_yacc(msg); - scaled_imu2->zacc = mavlink_msg_scaled_imu2_get_zacc(msg); - scaled_imu2->xgyro = mavlink_msg_scaled_imu2_get_xgyro(msg); - scaled_imu2->ygyro = mavlink_msg_scaled_imu2_get_ygyro(msg); - scaled_imu2->zgyro = mavlink_msg_scaled_imu2_get_zgyro(msg); - scaled_imu2->xmag = mavlink_msg_scaled_imu2_get_xmag(msg); - scaled_imu2->ymag = mavlink_msg_scaled_imu2_get_ymag(msg); - scaled_imu2->zmag = mavlink_msg_scaled_imu2_get_zmag(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_IMU2_LEN? msg->len : MAVLINK_MSG_ID_SCALED_IMU2_LEN; - memset(scaled_imu2, 0, MAVLINK_MSG_ID_SCALED_IMU2_LEN); - memcpy(scaled_imu2, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_scaled_imu3.h b/include/mavlink/v2.0/common/mavlink_msg_scaled_imu3.h deleted file mode 100644 index 22b9d86..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_scaled_imu3.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE SCALED_IMU3 PACKING - -#define MAVLINK_MSG_ID_SCALED_IMU3 129 - -MAVPACKED( -typedef struct __mavlink_scaled_imu3_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - int16_t xacc; /*< X acceleration (mg)*/ - int16_t yacc; /*< Y acceleration (mg)*/ - int16_t zacc; /*< Z acceleration (mg)*/ - int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ - int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ - int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ - int16_t xmag; /*< X Magnetic field (milli tesla)*/ - int16_t ymag; /*< Y Magnetic field (milli tesla)*/ - int16_t zmag; /*< Z Magnetic field (milli tesla)*/ -}) mavlink_scaled_imu3_t; - -#define MAVLINK_MSG_ID_SCALED_IMU3_LEN 22 -#define MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN 22 -#define MAVLINK_MSG_ID_129_LEN 22 -#define MAVLINK_MSG_ID_129_MIN_LEN 22 - -#define MAVLINK_MSG_ID_SCALED_IMU3_CRC 46 -#define MAVLINK_MSG_ID_129_CRC 46 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_IMU3 { \ - 129, \ - "SCALED_IMU3", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu3_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu3_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu3_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu3_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu3_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu3_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu3_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu3_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu3_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu3_t, zmag) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_IMU3 { \ - "SCALED_IMU3", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu3_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu3_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu3_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu3_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu3_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu3_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu3_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu3_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu3_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu3_t, zmag) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_imu3 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_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#else - mavlink_scaled_imu3_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -} - -/** - * @brief Pack a scaled_imu3 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#else - mavlink_scaled_imu3_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -} - -/** - * @brief Encode a scaled_imu3 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_imu3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3) -{ - return mavlink_msg_scaled_imu3_pack(system_id, component_id, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag); -} - -/** - * @brief Encode a scaled_imu3 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_imu3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3) -{ - return mavlink_msg_scaled_imu3_pack_chan(system_id, component_id, chan, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag); -} - -/** - * @brief Send a scaled_imu3 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_imu3_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[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#else - mavlink_scaled_imu3_t packet; - packet.time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#endif -} - -/** - * @brief Send a scaled_imu3 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_imu3_send_struct(mavlink_channel_t chan, const mavlink_scaled_imu3_t* scaled_imu3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_imu3_send(chan, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)scaled_imu3, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_IMU3_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_imu3_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#else - mavlink_scaled_imu3_t *packet = (mavlink_scaled_imu3_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - 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; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_IMU3 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_imu3 message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_imu3_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field xacc from scaled_imu3 message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field yacc from scaled_imu3 message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field zacc from scaled_imu3 message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field xgyro from scaled_imu3 message - * - * @return Angular speed around X axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field ygyro from scaled_imu3 message - * - * @return Angular speed around Y axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field zgyro from scaled_imu3 message - * - * @return Angular speed around Z axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field xmag from scaled_imu3 message - * - * @return X Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field ymag from scaled_imu3 message - * - * @return Y Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field zmag from scaled_imu3 message - * - * @return Z Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu3_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Decode a scaled_imu3 message into a struct - * - * @param msg The message to decode - * @param scaled_imu3 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_imu3_decode(const mavlink_message_t* msg, mavlink_scaled_imu3_t* scaled_imu3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_imu3->time_boot_ms = mavlink_msg_scaled_imu3_get_time_boot_ms(msg); - scaled_imu3->xacc = mavlink_msg_scaled_imu3_get_xacc(msg); - scaled_imu3->yacc = mavlink_msg_scaled_imu3_get_yacc(msg); - scaled_imu3->zacc = mavlink_msg_scaled_imu3_get_zacc(msg); - scaled_imu3->xgyro = mavlink_msg_scaled_imu3_get_xgyro(msg); - scaled_imu3->ygyro = mavlink_msg_scaled_imu3_get_ygyro(msg); - scaled_imu3->zgyro = mavlink_msg_scaled_imu3_get_zgyro(msg); - scaled_imu3->xmag = mavlink_msg_scaled_imu3_get_xmag(msg); - scaled_imu3->ymag = mavlink_msg_scaled_imu3_get_ymag(msg); - scaled_imu3->zmag = mavlink_msg_scaled_imu3_get_zmag(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_IMU3_LEN? msg->len : MAVLINK_MSG_ID_SCALED_IMU3_LEN; - memset(scaled_imu3, 0, MAVLINK_MSG_ID_SCALED_IMU3_LEN); - memcpy(scaled_imu3, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_scaled_pressure.h b/include/mavlink/v2.0/common/mavlink_msg_scaled_pressure.h deleted file mode 100644 index 0dcfc92..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_scaled_pressure.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE SCALED_PRESSURE PACKING - -#define MAVLINK_MSG_ID_SCALED_PRESSURE 29 - -MAVPACKED( -typedef struct __mavlink_scaled_pressure_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float press_abs; /*< Absolute pressure (hectopascal)*/ - float press_diff; /*< Differential pressure 1 (hectopascal)*/ - int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ -}) mavlink_scaled_pressure_t; - -#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14 -#define MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN 14 -#define MAVLINK_MSG_ID_29_LEN 14 -#define MAVLINK_MSG_ID_29_MIN_LEN 14 - -#define MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115 -#define MAVLINK_MSG_ID_29_CRC 115 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ - 29, \ - "SCALED_PRESSURE", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ - "SCALED_PRESSURE", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_pressure 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_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - 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, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -} - -/** - * @brief Pack a scaled_pressure message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - 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, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -} - -/** - * @brief Encode a scaled_pressure struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) -{ - return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); -} - -/** - * @brief Encode a scaled_pressure struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) -{ - return mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, chan, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); -} - -/** - * @brief Send a scaled_pressure message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#endif -} - -/** - * @brief Send a scaled_pressure message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_pressure_send_struct(mavlink_channel_t chan, const mavlink_scaled_pressure_t* scaled_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_pressure_send(chan, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)scaled_pressure, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_pressure_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - mavlink_scaled_pressure_t *packet = (mavlink_scaled_pressure_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->press_abs = press_abs; - packet->press_diff = press_diff; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_PRESSURE UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_pressure message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field press_abs from scaled_pressure message - * - * @return Absolute pressure (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field press_diff from scaled_pressure message - * - * @return Differential pressure 1 (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field temperature from scaled_pressure message - * - * @return Temperature measurement (0.01 degrees celsius) - */ -static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Decode a scaled_pressure message into a struct - * - * @param msg The message to decode - * @param scaled_pressure C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_pressure->time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg); - scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg); - scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg); - scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_PRESSURE_LEN? msg->len : MAVLINK_MSG_ID_SCALED_PRESSURE_LEN; - memset(scaled_pressure, 0, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); - memcpy(scaled_pressure, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_scaled_pressure2.h b/include/mavlink/v2.0/common/mavlink_msg_scaled_pressure2.h deleted file mode 100644 index 1e7920b..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_scaled_pressure2.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE SCALED_PRESSURE2 PACKING - -#define MAVLINK_MSG_ID_SCALED_PRESSURE2 137 - -MAVPACKED( -typedef struct __mavlink_scaled_pressure2_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float press_abs; /*< Absolute pressure (hectopascal)*/ - float press_diff; /*< Differential pressure 1 (hectopascal)*/ - int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ -}) mavlink_scaled_pressure2_t; - -#define MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN 14 -#define MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN 14 -#define MAVLINK_MSG_ID_137_LEN 14 -#define MAVLINK_MSG_ID_137_MIN_LEN 14 - -#define MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC 195 -#define MAVLINK_MSG_ID_137_CRC 195 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2 { \ - 137, \ - "SCALED_PRESSURE2", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure2_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure2_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure2_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure2_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2 { \ - "SCALED_PRESSURE2", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure2_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure2_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure2_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure2_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_pressure2 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_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_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, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#else - mavlink_scaled_pressure2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE2; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -} - -/** - * @brief Pack a scaled_pressure2 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_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, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#else - mavlink_scaled_pressure2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE2; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -} - -/** - * @brief Encode a scaled_pressure2 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure2_t* scaled_pressure2) -{ - return mavlink_msg_scaled_pressure2_pack(system_id, component_id, msg, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature); -} - -/** - * @brief Encode a scaled_pressure2 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure2_t* scaled_pressure2) -{ - return mavlink_msg_scaled_pressure2_pack_chan(system_id, component_id, chan, msg, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature); -} - -/** - * @brief Send a scaled_pressure2 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_pressure2_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[MAVLINK_MSG_ID_SCALED_PRESSURE2_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_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#else - mavlink_scaled_pressure2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#endif -} - -/** - * @brief Send a scaled_pressure2 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_pressure2_send_struct(mavlink_channel_t chan, const mavlink_scaled_pressure2_t* scaled_pressure2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_pressure2_send(chan, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)scaled_pressure2, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_pressure2_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#else - mavlink_scaled_pressure2_t *packet = (mavlink_scaled_pressure2_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->press_abs = press_abs; - packet->press_diff = press_diff; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_PRESSURE2 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_pressure2 message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_pressure2_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field press_abs from scaled_pressure2 message - * - * @return Absolute pressure (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure2_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field press_diff from scaled_pressure2 message - * - * @return Differential pressure 1 (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure2_get_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field temperature from scaled_pressure2 message - * - * @return Temperature measurement (0.01 degrees celsius) - */ -static inline int16_t mavlink_msg_scaled_pressure2_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Decode a scaled_pressure2 message into a struct - * - * @param msg The message to decode - * @param scaled_pressure2 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_pressure2_decode(const mavlink_message_t* msg, mavlink_scaled_pressure2_t* scaled_pressure2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_pressure2->time_boot_ms = mavlink_msg_scaled_pressure2_get_time_boot_ms(msg); - scaled_pressure2->press_abs = mavlink_msg_scaled_pressure2_get_press_abs(msg); - scaled_pressure2->press_diff = mavlink_msg_scaled_pressure2_get_press_diff(msg); - scaled_pressure2->temperature = mavlink_msg_scaled_pressure2_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN? msg->len : MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN; - memset(scaled_pressure2, 0, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); - memcpy(scaled_pressure2, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_scaled_pressure3.h b/include/mavlink/v2.0/common/mavlink_msg_scaled_pressure3.h deleted file mode 100644 index a0b6586..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_scaled_pressure3.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE SCALED_PRESSURE3 PACKING - -#define MAVLINK_MSG_ID_SCALED_PRESSURE3 143 - -MAVPACKED( -typedef struct __mavlink_scaled_pressure3_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float press_abs; /*< Absolute pressure (hectopascal)*/ - float press_diff; /*< Differential pressure 1 (hectopascal)*/ - int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ -}) mavlink_scaled_pressure3_t; - -#define MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN 14 -#define MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN 14 -#define MAVLINK_MSG_ID_143_LEN 14 -#define MAVLINK_MSG_ID_143_MIN_LEN 14 - -#define MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC 131 -#define MAVLINK_MSG_ID_143_CRC 131 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3 { \ - 143, \ - "SCALED_PRESSURE3", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure3_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure3_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure3_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure3_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3 { \ - "SCALED_PRESSURE3", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure3_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure3_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure3_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure3_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_pressure3 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_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_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, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#else - mavlink_scaled_pressure3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE3; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -} - -/** - * @brief Pack a scaled_pressure3 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_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, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#else - mavlink_scaled_pressure3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE3; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -} - -/** - * @brief Encode a scaled_pressure3 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure3_t* scaled_pressure3) -{ - return mavlink_msg_scaled_pressure3_pack(system_id, component_id, msg, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature); -} - -/** - * @brief Encode a scaled_pressure3 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure3_t* scaled_pressure3) -{ - return mavlink_msg_scaled_pressure3_pack_chan(system_id, component_id, chan, msg, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature); -} - -/** - * @brief Send a scaled_pressure3 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_pressure3_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[MAVLINK_MSG_ID_SCALED_PRESSURE3_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_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#else - mavlink_scaled_pressure3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#endif -} - -/** - * @brief Send a scaled_pressure3 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_pressure3_send_struct(mavlink_channel_t chan, const mavlink_scaled_pressure3_t* scaled_pressure3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_pressure3_send(chan, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)scaled_pressure3, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_pressure3_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#else - mavlink_scaled_pressure3_t *packet = (mavlink_scaled_pressure3_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->press_abs = press_abs; - packet->press_diff = press_diff; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_PRESSURE3 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_pressure3 message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_pressure3_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field press_abs from scaled_pressure3 message - * - * @return Absolute pressure (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure3_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field press_diff from scaled_pressure3 message - * - * @return Differential pressure 1 (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure3_get_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field temperature from scaled_pressure3 message - * - * @return Temperature measurement (0.01 degrees celsius) - */ -static inline int16_t mavlink_msg_scaled_pressure3_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Decode a scaled_pressure3 message into a struct - * - * @param msg The message to decode - * @param scaled_pressure3 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_pressure3_decode(const mavlink_message_t* msg, mavlink_scaled_pressure3_t* scaled_pressure3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_pressure3->time_boot_ms = mavlink_msg_scaled_pressure3_get_time_boot_ms(msg); - scaled_pressure3->press_abs = mavlink_msg_scaled_pressure3_get_press_abs(msg); - scaled_pressure3->press_diff = mavlink_msg_scaled_pressure3_get_press_diff(msg); - scaled_pressure3->temperature = mavlink_msg_scaled_pressure3_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN? msg->len : MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN; - memset(scaled_pressure3, 0, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); - memcpy(scaled_pressure3, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_serial_control.h b/include/mavlink/v2.0/common/mavlink_msg_serial_control.h deleted file mode 100644 index ce95811..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_serial_control.h +++ /dev/null @@ -1,330 +0,0 @@ -#pragma once -// MESSAGE SERIAL_CONTROL PACKING - -#define MAVLINK_MSG_ID_SERIAL_CONTROL 126 - -MAVPACKED( -typedef struct __mavlink_serial_control_t { - uint32_t baudrate; /*< Baudrate of transfer. Zero means no change.*/ - uint16_t timeout; /*< Timeout for reply data in milliseconds*/ - uint8_t device; /*< See SERIAL_CONTROL_DEV enum*/ - uint8_t flags; /*< See SERIAL_CONTROL_FLAG enum*/ - uint8_t count; /*< how many bytes in this transfer*/ - uint8_t data[70]; /*< serial data*/ -}) mavlink_serial_control_t; - -#define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79 -#define MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN 79 -#define MAVLINK_MSG_ID_126_LEN 79 -#define MAVLINK_MSG_ID_126_MIN_LEN 79 - -#define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220 -#define MAVLINK_MSG_ID_126_CRC 220 - -#define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN 70 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \ - 126, \ - "SERIAL_CONTROL", \ - 6, \ - { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ - { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \ - "SERIAL_CONTROL", \ - 6, \ - { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ - { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a serial_control 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 device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -} - -/** - * @brief Pack a serial_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t device,uint8_t flags,uint16_t timeout,uint32_t baudrate,uint8_t count,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -} - -/** - * @brief Encode a serial_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) -{ - return mavlink_msg_serial_control_pack(system_id, component_id, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); -} - -/** - * @brief Encode a serial_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) -{ - return mavlink_msg_serial_control_pack_chan(system_id, component_id, chan, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); -} - -/** - * @brief Send a serial_control message - * @param chan MAVLink channel to send the message - * - * @param device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_control_send(mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#endif -} - -/** - * @brief Send a serial_control message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_serial_control_send_struct(mavlink_channel_t chan, const mavlink_serial_control_t* serial_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_serial_control_send(chan, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)serial_control, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - mavlink_serial_control_t *packet = (mavlink_serial_control_t *)msgbuf; - packet->baudrate = baudrate; - packet->timeout = timeout; - packet->device = device; - packet->flags = flags; - packet->count = count; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_CONTROL UNPACKING - - -/** - * @brief Get field device from serial_control message - * - * @return See SERIAL_CONTROL_DEV enum - */ -static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field flags from serial_control message - * - * @return See SERIAL_CONTROL_FLAG enum - */ -static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field timeout from serial_control message - * - * @return Timeout for reply data in milliseconds - */ -static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field baudrate from serial_control message - * - * @return Baudrate of transfer. Zero means no change. - */ -static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from serial_control message - * - * @return how many bytes in this transfer - */ -static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field data from serial_control message - * - * @return serial data - */ -static inline uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 70, 9); -} - -/** - * @brief Decode a serial_control message into a struct - * - * @param msg The message to decode - * @param serial_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_control_decode(const mavlink_message_t* msg, mavlink_serial_control_t* serial_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - serial_control->baudrate = mavlink_msg_serial_control_get_baudrate(msg); - serial_control->timeout = mavlink_msg_serial_control_get_timeout(msg); - serial_control->device = mavlink_msg_serial_control_get_device(msg); - serial_control->flags = mavlink_msg_serial_control_get_flags(msg); - serial_control->count = mavlink_msg_serial_control_get_count(msg); - mavlink_msg_serial_control_get_data(msg, serial_control->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SERIAL_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_SERIAL_CONTROL_LEN; - memset(serial_control, 0, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); - memcpy(serial_control, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_servo_output_raw.h b/include/mavlink/v2.0/common/mavlink_msg_servo_output_raw.h deleted file mode 100644 index 48ff94a..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_servo_output_raw.h +++ /dev/null @@ -1,638 +0,0 @@ -#pragma once -// MESSAGE SERVO_OUTPUT_RAW PACKING - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36 - -MAVPACKED( -typedef struct __mavlink_servo_output_raw_t { - uint32_t time_usec; /*< Timestamp (microseconds since system boot)*/ - uint16_t servo1_raw; /*< Servo output 1 value, in microseconds*/ - uint16_t servo2_raw; /*< Servo output 2 value, in microseconds*/ - uint16_t servo3_raw; /*< Servo output 3 value, in microseconds*/ - uint16_t servo4_raw; /*< Servo output 4 value, in microseconds*/ - uint16_t servo5_raw; /*< Servo output 5 value, in microseconds*/ - uint16_t servo6_raw; /*< Servo output 6 value, in microseconds*/ - uint16_t servo7_raw; /*< Servo output 7 value, in microseconds*/ - uint16_t servo8_raw; /*< Servo output 8 value, in microseconds*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.*/ - uint16_t servo9_raw; /*< Servo output 9 value, in microseconds*/ - uint16_t servo10_raw; /*< Servo output 10 value, in microseconds*/ - uint16_t servo11_raw; /*< Servo output 11 value, in microseconds*/ - uint16_t servo12_raw; /*< Servo output 12 value, in microseconds*/ - uint16_t servo13_raw; /*< Servo output 13 value, in microseconds*/ - uint16_t servo14_raw; /*< Servo output 14 value, in microseconds*/ - uint16_t servo15_raw; /*< Servo output 15 value, in microseconds*/ - uint16_t servo16_raw; /*< Servo output 16 value, in microseconds*/ -}) mavlink_servo_output_raw_t; - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 37 -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN 21 -#define MAVLINK_MSG_ID_36_LEN 37 -#define MAVLINK_MSG_ID_36_MIN_LEN 21 - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC 222 -#define MAVLINK_MSG_ID_36_CRC 222 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ - 36, \ - "SERVO_OUTPUT_RAW", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ - { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ - { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ - { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ - { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ - { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ - { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ - { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ - { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ - { "servo9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 21, offsetof(mavlink_servo_output_raw_t, servo9_raw) }, \ - { "servo10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 23, offsetof(mavlink_servo_output_raw_t, servo10_raw) }, \ - { "servo11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 25, offsetof(mavlink_servo_output_raw_t, servo11_raw) }, \ - { "servo12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 27, offsetof(mavlink_servo_output_raw_t, servo12_raw) }, \ - { "servo13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 29, offsetof(mavlink_servo_output_raw_t, servo13_raw) }, \ - { "servo14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 31, offsetof(mavlink_servo_output_raw_t, servo14_raw) }, \ - { "servo15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 33, offsetof(mavlink_servo_output_raw_t, servo15_raw) }, \ - { "servo16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_servo_output_raw_t, servo16_raw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ - "SERVO_OUTPUT_RAW", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ - { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ - { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ - { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ - { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ - { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ - { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ - { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ - { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ - { "servo9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 21, offsetof(mavlink_servo_output_raw_t, servo9_raw) }, \ - { "servo10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 23, offsetof(mavlink_servo_output_raw_t, servo10_raw) }, \ - { "servo11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 25, offsetof(mavlink_servo_output_raw_t, servo11_raw) }, \ - { "servo12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 27, offsetof(mavlink_servo_output_raw_t, servo12_raw) }, \ - { "servo13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 29, offsetof(mavlink_servo_output_raw_t, servo13_raw) }, \ - { "servo14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 31, offsetof(mavlink_servo_output_raw_t, servo14_raw) }, \ - { "servo15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 33, offsetof(mavlink_servo_output_raw_t, servo15_raw) }, \ - { "servo16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_servo_output_raw_t, servo16_raw) }, \ - } \ -} -#endif - -/** - * @brief Pack a servo_output_raw 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 since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds - * @param servo9_raw Servo output 9 value, in microseconds - * @param servo10_raw Servo output 10 value, in microseconds - * @param servo11_raw Servo output 11 value, in microseconds - * @param servo12_raw Servo output 12 value, in microseconds - * @param servo13_raw Servo output 13 value, in microseconds - * @param servo14_raw Servo output 14 value, in microseconds - * @param servo15_raw Servo output 15 value, in microseconds - * @param servo16_raw Servo output 16 value, in microseconds - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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, uint16_t servo9_raw, uint16_t servo10_raw, uint16_t servo11_raw, uint16_t servo12_raw, uint16_t servo13_raw, uint16_t servo14_raw, uint16_t servo15_raw, uint16_t servo16_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint16_t(buf, 21, servo9_raw); - _mav_put_uint16_t(buf, 23, servo10_raw); - _mav_put_uint16_t(buf, 25, servo11_raw); - _mav_put_uint16_t(buf, 27, servo12_raw); - _mav_put_uint16_t(buf, 29, servo13_raw); - _mav_put_uint16_t(buf, 31, servo14_raw); - _mav_put_uint16_t(buf, 33, servo15_raw); - _mav_put_uint16_t(buf, 35, servo16_raw); - - 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; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - packet.servo9_raw = servo9_raw; - packet.servo10_raw = servo10_raw; - packet.servo11_raw = servo11_raw; - packet.servo12_raw = servo12_raw; - packet.servo13_raw = servo13_raw; - packet.servo14_raw = servo14_raw; - packet.servo15_raw = servo15_raw; - packet.servo16_raw = servo16_raw; - - 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, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -} - -/** - * @brief Pack a servo_output_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds - * @param servo9_raw Servo output 9 value, in microseconds - * @param servo10_raw Servo output 10 value, in microseconds - * @param servo11_raw Servo output 11 value, in microseconds - * @param servo12_raw Servo output 12 value, in microseconds - * @param servo13_raw Servo output 13 value, in microseconds - * @param servo14_raw Servo output 14 value, in microseconds - * @param servo15_raw Servo output 15 value, in microseconds - * @param servo16_raw Servo output 16 value, in microseconds - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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,uint16_t servo9_raw,uint16_t servo10_raw,uint16_t servo11_raw,uint16_t servo12_raw,uint16_t servo13_raw,uint16_t servo14_raw,uint16_t servo15_raw,uint16_t servo16_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint16_t(buf, 21, servo9_raw); - _mav_put_uint16_t(buf, 23, servo10_raw); - _mav_put_uint16_t(buf, 25, servo11_raw); - _mav_put_uint16_t(buf, 27, servo12_raw); - _mav_put_uint16_t(buf, 29, servo13_raw); - _mav_put_uint16_t(buf, 31, servo14_raw); - _mav_put_uint16_t(buf, 33, servo15_raw); - _mav_put_uint16_t(buf, 35, servo16_raw); - - 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; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - packet.servo9_raw = servo9_raw; - packet.servo10_raw = servo10_raw; - packet.servo11_raw = servo11_raw; - packet.servo12_raw = servo12_raw; - packet.servo13_raw = servo13_raw; - packet.servo14_raw = servo14_raw; - packet.servo15_raw = servo15_raw; - packet.servo16_raw = servo16_raw; - - 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, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -} - -/** - * @brief Encode a servo_output_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param servo_output_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) -{ - return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw, servo_output_raw->servo9_raw, servo_output_raw->servo10_raw, servo_output_raw->servo11_raw, servo_output_raw->servo12_raw, servo_output_raw->servo13_raw, servo_output_raw->servo14_raw, servo_output_raw->servo15_raw, servo_output_raw->servo16_raw); -} - -/** - * @brief Encode a servo_output_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param servo_output_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_servo_output_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) -{ - return mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, chan, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw, servo_output_raw->servo9_raw, servo_output_raw->servo10_raw, servo_output_raw->servo11_raw, servo_output_raw->servo12_raw, servo_output_raw->servo13_raw, servo_output_raw->servo14_raw, servo_output_raw->servo15_raw, servo_output_raw->servo16_raw); -} - -/** - * @brief Send a servo_output_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds - * @param servo9_raw Servo output 9 value, in microseconds - * @param servo10_raw Servo output 10 value, in microseconds - * @param servo11_raw Servo output 11 value, in microseconds - * @param servo12_raw Servo output 12 value, in microseconds - * @param servo13_raw Servo output 13 value, in microseconds - * @param servo14_raw Servo output 14 value, in microseconds - * @param servo15_raw Servo output 15 value, in microseconds - * @param servo16_raw Servo output 16 value, in microseconds - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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, uint16_t servo9_raw, uint16_t servo10_raw, uint16_t servo11_raw, uint16_t servo12_raw, uint16_t servo13_raw, uint16_t servo14_raw, uint16_t servo15_raw, uint16_t servo16_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint16_t(buf, 21, servo9_raw); - _mav_put_uint16_t(buf, 23, servo10_raw); - _mav_put_uint16_t(buf, 25, servo11_raw); - _mav_put_uint16_t(buf, 27, servo12_raw); - _mav_put_uint16_t(buf, 29, servo13_raw); - _mav_put_uint16_t(buf, 31, servo14_raw); - _mav_put_uint16_t(buf, 33, servo15_raw); - _mav_put_uint16_t(buf, 35, servo16_raw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - mavlink_servo_output_raw_t packet; - packet.time_usec = time_usec; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - packet.servo9_raw = servo9_raw; - packet.servo10_raw = servo10_raw; - packet.servo11_raw = servo11_raw; - packet.servo12_raw = servo12_raw; - packet.servo13_raw = servo13_raw; - packet.servo14_raw = servo14_raw; - packet.servo15_raw = servo15_raw; - packet.servo16_raw = servo16_raw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#endif -} - -/** - * @brief Send a servo_output_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_servo_output_raw_send_struct(mavlink_channel_t chan, const mavlink_servo_output_raw_t* servo_output_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_servo_output_raw_send(chan, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw, servo_output_raw->servo9_raw, servo_output_raw->servo10_raw, servo_output_raw->servo11_raw, servo_output_raw->servo12_raw, servo_output_raw->servo13_raw, servo_output_raw->servo14_raw, servo_output_raw->servo15_raw, servo_output_raw->servo16_raw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)servo_output_raw, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_servo_output_raw_send_buf(mavlink_message_t *msgbuf, 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, uint16_t servo9_raw, uint16_t servo10_raw, uint16_t servo11_raw, uint16_t servo12_raw, uint16_t servo13_raw, uint16_t servo14_raw, uint16_t servo15_raw, uint16_t servo16_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 4, servo1_raw); - _mav_put_uint16_t(buf, 6, servo2_raw); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint16_t(buf, 21, servo9_raw); - _mav_put_uint16_t(buf, 23, servo10_raw); - _mav_put_uint16_t(buf, 25, servo11_raw); - _mav_put_uint16_t(buf, 27, servo12_raw); - _mav_put_uint16_t(buf, 29, servo13_raw); - _mav_put_uint16_t(buf, 31, servo14_raw); - _mav_put_uint16_t(buf, 33, servo15_raw); - _mav_put_uint16_t(buf, 35, servo16_raw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - mavlink_servo_output_raw_t *packet = (mavlink_servo_output_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->servo1_raw = servo1_raw; - packet->servo2_raw = servo2_raw; - packet->servo3_raw = servo3_raw; - packet->servo4_raw = servo4_raw; - packet->servo5_raw = servo5_raw; - packet->servo6_raw = servo6_raw; - packet->servo7_raw = servo7_raw; - packet->servo8_raw = servo8_raw; - packet->port = port; - packet->servo9_raw = servo9_raw; - packet->servo10_raw = servo10_raw; - packet->servo11_raw = servo11_raw; - packet->servo12_raw = servo12_raw; - packet->servo13_raw = servo13_raw; - packet->servo14_raw = servo14_raw; - packet->servo15_raw = servo15_raw; - packet->servo16_raw = servo16_raw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SERVO_OUTPUT_RAW UNPACKING - - -/** - * @brief Get field time_usec from servo_output_raw message - * - * @return Timestamp (microseconds since system boot) - */ -static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from servo_output_raw message - * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - */ -static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field servo1_raw from servo_output_raw message - * - * @return Servo output 1 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field servo2_raw from servo_output_raw message - * - * @return Servo output 2 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field servo3_raw from servo_output_raw message - * - * @return Servo output 3 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field servo4_raw from servo_output_raw message - * - * @return Servo output 4 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field servo5_raw from servo_output_raw message - * - * @return Servo output 5 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field servo6_raw from servo_output_raw message - * - * @return Servo output 6 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field servo7_raw from servo_output_raw message - * - * @return Servo output 7 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field servo8_raw from servo_output_raw message - * - * @return Servo output 8 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field servo9_raw from servo_output_raw message - * - * @return Servo output 9 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo9_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 21); -} - -/** - * @brief Get field servo10_raw from servo_output_raw message - * - * @return Servo output 10 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo10_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 23); -} - -/** - * @brief Get field servo11_raw from servo_output_raw message - * - * @return Servo output 11 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo11_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 25); -} - -/** - * @brief Get field servo12_raw from servo_output_raw message - * - * @return Servo output 12 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo12_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 27); -} - -/** - * @brief Get field servo13_raw from servo_output_raw message - * - * @return Servo output 13 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo13_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 29); -} - -/** - * @brief Get field servo14_raw from servo_output_raw message - * - * @return Servo output 14 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo14_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 31); -} - -/** - * @brief Get field servo15_raw from servo_output_raw message - * - * @return Servo output 15 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo15_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 33); -} - -/** - * @brief Get field servo16_raw from servo_output_raw message - * - * @return Servo output 16 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo16_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 35); -} - -/** - * @brief Decode a servo_output_raw message into a struct - * - * @param msg The message to decode - * @param servo_output_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - servo_output_raw->time_usec = mavlink_msg_servo_output_raw_get_time_usec(msg); - servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg); - servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg); - servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg); - servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg); - servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg); - servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg); - servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg); - 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); - servo_output_raw->servo9_raw = mavlink_msg_servo_output_raw_get_servo9_raw(msg); - servo_output_raw->servo10_raw = mavlink_msg_servo_output_raw_get_servo10_raw(msg); - servo_output_raw->servo11_raw = mavlink_msg_servo_output_raw_get_servo11_raw(msg); - servo_output_raw->servo12_raw = mavlink_msg_servo_output_raw_get_servo12_raw(msg); - servo_output_raw->servo13_raw = mavlink_msg_servo_output_raw_get_servo13_raw(msg); - servo_output_raw->servo14_raw = mavlink_msg_servo_output_raw_get_servo14_raw(msg); - servo_output_raw->servo15_raw = mavlink_msg_servo_output_raw_get_servo15_raw(msg); - servo_output_raw->servo16_raw = mavlink_msg_servo_output_raw_get_servo16_raw(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN? msg->len : MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN; - memset(servo_output_raw, 0, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); - memcpy(servo_output_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_set_actuator_control_target.h b/include/mavlink/v2.0/common/mavlink_msg_set_actuator_control_target.h deleted file mode 100644 index f804d4b..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_set_actuator_control_target.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE SET_ACTUATOR_CONTROL_TARGET PACKING - -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET 139 - -MAVPACKED( -typedef struct __mavlink_set_actuator_control_target_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ - uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -}) mavlink_set_actuator_control_target_t; - -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN 43 -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN 43 -#define MAVLINK_MSG_ID_139_LEN 43 -#define MAVLINK_MSG_ID_139_MIN_LEN 43 - -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC 168 -#define MAVLINK_MSG_ID_139_CRC 168 - -#define MAVLINK_MSG_SET_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET { \ - 139, \ - "SET_ACTUATOR_CONTROL_TARGET", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_set_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_set_actuator_control_target_t, group_mlx) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_set_actuator_control_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_actuator_control_target_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET { \ - "SET_ACTUATOR_CONTROL_TARGET", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_set_actuator_control_target_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_set_actuator_control_target_t, group_mlx) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_set_actuator_control_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_actuator_control_target_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_actuator_control_target 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 (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_set_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Pack a set_actuator_control_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t group_mlx,uint8_t target_system,uint8_t target_component,const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_set_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Encode a set_actuator_control_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ - return mavlink_msg_set_actuator_control_target_pack(system_id, component_id, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); -} - -/** - * @brief Encode a set_actuator_control_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ - return mavlink_msg_set_actuator_control_target_pack_chan(system_id, component_id, chan, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); -} - -/** - * @brief Send a set_actuator_control_target message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_set_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -/** - * @brief Send a set_actuator_control_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_actuator_control_target_send_struct(mavlink_channel_t chan, const mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_actuator_control_target_send(chan, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)set_actuator_control_target, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_set_actuator_control_target_t *packet = (mavlink_set_actuator_control_target_t *)msgbuf; - packet->time_usec = time_usec; - packet->group_mlx = group_mlx; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_ACTUATOR_CONTROL_TARGET UNPACKING - - -/** - * @brief Get field time_usec from set_actuator_control_target message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_set_actuator_control_target_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field group_mlx from set_actuator_control_target message - * - * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - */ -static inline uint8_t mavlink_msg_set_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field target_system from set_actuator_control_target message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Get field target_component from set_actuator_control_target message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field controls from set_actuator_control_target message - * - * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) -{ - return _MAV_RETURN_float_array(msg, controls, 8, 8); -} - -/** - * @brief Decode a set_actuator_control_target message into a struct - * - * @param msg The message to decode - * @param set_actuator_control_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_actuator_control_target->time_usec = mavlink_msg_set_actuator_control_target_get_time_usec(msg); - mavlink_msg_set_actuator_control_target_get_controls(msg, set_actuator_control_target->controls); - set_actuator_control_target->group_mlx = mavlink_msg_set_actuator_control_target_get_group_mlx(msg); - set_actuator_control_target->target_system = mavlink_msg_set_actuator_control_target_get_target_system(msg); - set_actuator_control_target->target_component = mavlink_msg_set_actuator_control_target_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN? msg->len : MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN; - memset(set_actuator_control_target, 0, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); - memcpy(set_actuator_control_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_set_attitude_target.h b/include/mavlink/v2.0/common/mavlink_msg_set_attitude_target.h deleted file mode 100644 index 1b68caa..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_set_attitude_target.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE SET_ATTITUDE_TARGET PACKING - -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET 82 - -MAVPACKED( -typedef struct __mavlink_set_attitude_target_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float body_roll_rate; /*< Body roll rate in radians per second*/ - float body_pitch_rate; /*< Body roll rate in radians per second*/ - float body_yaw_rate; /*< Body roll rate in radians per second*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude*/ -}) mavlink_set_attitude_target_t; - -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN 39 -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN 39 -#define MAVLINK_MSG_ID_82_LEN 39 -#define MAVLINK_MSG_ID_82_MIN_LEN 39 - -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC 49 -#define MAVLINK_MSG_ID_82_CRC 49 - -#define MAVLINK_MSG_SET_ATTITUDE_TARGET_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET { \ - 82, \ - "SET_ATTITUDE_TARGET", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET { \ - "SET_ATTITUDE_TARGET", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_attitude_target 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_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#else - mavlink_set_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Pack a set_attitude_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#else - mavlink_set_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Encode a set_attitude_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target) -{ - return mavlink_msg_set_attitude_target_pack(system_id, component_id, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust); -} - -/** - * @brief Encode a set_attitude_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target) -{ - return mavlink_msg_set_attitude_target_pack_chan(system_id, component_id, chan, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust); -} - -/** - * @brief Send a set_attitude_target message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate Body roll rate in radians per second - * @param body_pitch_rate Body roll rate in radians per second - * @param body_yaw_rate Body roll rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#else - mavlink_set_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#endif -} - -/** - * @brief Send a set_attitude_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_attitude_target_send_struct(mavlink_channel_t chan, const mavlink_set_attitude_target_t* set_attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_attitude_target_send(chan, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)set_attitude_target, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#else - mavlink_set_attitude_target_t *packet = (mavlink_set_attitude_target_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->body_roll_rate = body_roll_rate; - packet->body_pitch_rate = body_pitch_rate; - packet->body_yaw_rate = body_yaw_rate; - packet->thrust = thrust; - packet->target_system = target_system; - packet->target_component = target_component; - packet->type_mask = type_mask; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_ATTITUDE_TARGET UNPACKING - - -/** - * @brief Get field time_boot_ms from set_attitude_target message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_set_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field target_system from set_attitude_target message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_attitude_target_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field target_component from set_attitude_target message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_attitude_target_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 37); -} - -/** - * @brief Get field type_mask from set_attitude_target message - * - * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - */ -static inline uint8_t mavlink_msg_set_attitude_target_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 38); -} - -/** - * @brief Get field q from set_attitude_target message - * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_set_attitude_target_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 4); -} - -/** - * @brief Get field body_roll_rate from set_attitude_target message - * - * @return Body roll rate in radians per second - */ -static inline float mavlink_msg_set_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field body_pitch_rate from set_attitude_target message - * - * @return Body roll rate in radians per second - */ -static inline float mavlink_msg_set_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field body_yaw_rate from set_attitude_target message - * - * @return Body roll rate in radians per second - */ -static inline float mavlink_msg_set_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field thrust from set_attitude_target message - * - * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - */ -static inline float mavlink_msg_set_attitude_target_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Decode a set_attitude_target message into a struct - * - * @param msg The message to decode - * @param set_attitude_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_attitude_target_decode(const mavlink_message_t* msg, mavlink_set_attitude_target_t* set_attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_attitude_target->time_boot_ms = mavlink_msg_set_attitude_target_get_time_boot_ms(msg); - mavlink_msg_set_attitude_target_get_q(msg, set_attitude_target->q); - set_attitude_target->body_roll_rate = mavlink_msg_set_attitude_target_get_body_roll_rate(msg); - set_attitude_target->body_pitch_rate = mavlink_msg_set_attitude_target_get_body_pitch_rate(msg); - set_attitude_target->body_yaw_rate = mavlink_msg_set_attitude_target_get_body_yaw_rate(msg); - set_attitude_target->thrust = mavlink_msg_set_attitude_target_get_thrust(msg); - set_attitude_target->target_system = mavlink_msg_set_attitude_target_get_target_system(msg); - set_attitude_target->target_component = mavlink_msg_set_attitude_target_get_target_component(msg); - set_attitude_target->type_mask = mavlink_msg_set_attitude_target_get_type_mask(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN? msg->len : MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN; - memset(set_attitude_target, 0, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); - memcpy(set_attitude_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_set_gps_global_origin.h b/include/mavlink/v2.0/common/mavlink_msg_set_gps_global_origin.h deleted file mode 100644 index a934c19..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_set_gps_global_origin.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE SET_GPS_GLOBAL_ORIGIN PACKING - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48 - -MAVPACKED( -typedef struct __mavlink_set_gps_global_origin_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ - uint8_t target_system; /*< System ID*/ -}) mavlink_set_gps_global_origin_t; - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13 -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN 13 -#define MAVLINK_MSG_ID_48_LEN 13 -#define MAVLINK_MSG_ID_48_MIN_LEN 13 - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC 41 -#define MAVLINK_MSG_ID_48_CRC 41 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ - 48, \ - "SET_GPS_GLOBAL_ORIGIN", \ - 4, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ - "SET_GPS_GLOBAL_ORIGIN", \ - 4, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_gps_global_origin message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), 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[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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - - 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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Pack a set_gps_global_origin message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @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, - 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[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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - - 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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Encode a set_gps_global_origin struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ - return mavlink_msg_set_gps_global_origin_pack(system_id, component_id, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); -} - -/** - * @brief Encode a set_gps_global_origin struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ - return mavlink_msg_set_gps_global_origin_pack_chan(system_id, component_id, chan, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); -} - -/** - * @brief Send a set_gps_global_origin message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - */ -#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[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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -/** - * @brief Send a set_gps_global_origin message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_gps_global_origin_send_struct(mavlink_channel_t chan, const mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_gps_global_origin_send(chan, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)set_gps_global_origin, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_gps_global_origin_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - mavlink_set_gps_global_origin_t *packet = (mavlink_set_gps_global_origin_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->target_system = target_system; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_GPS_GLOBAL_ORIGIN UNPACKING - - -/** - * @brief Get field target_system from set_gps_global_origin message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field latitude from set_gps_global_origin message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from set_gps_global_origin message - * - * @return Longitude (WGS84, in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from set_gps_global_origin message - * - * @return Altitude (AMSL), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Decode a set_gps_global_origin message into a struct - * - * @param msg The message to decode - * @param set_gps_global_origin C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_gps_global_origin->latitude = mavlink_msg_set_gps_global_origin_get_latitude(msg); - set_gps_global_origin->longitude = mavlink_msg_set_gps_global_origin_get_longitude(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN? msg->len : MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN; - memset(set_gps_global_origin, 0, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); - memcpy(set_gps_global_origin, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_set_home_position.h b/include/mavlink/v2.0/common/mavlink_msg_set_home_position.h deleted file mode 100644 index cd7c8d3..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_set_home_position.h +++ /dev/null @@ -1,455 +0,0 @@ -#pragma once -// MESSAGE SET_HOME_POSITION PACKING - -#define MAVLINK_MSG_ID_SET_HOME_POSITION 243 - -MAVPACKED( -typedef struct __mavlink_set_home_position_t { - int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ - int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ - int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ - float x; /*< Local X position of this position in the local coordinate frame*/ - float y; /*< Local Y position of this position in the local coordinate frame*/ - float z; /*< Local Z position of this position in the local coordinate frame*/ - float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ - float approach_x; /*< Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_y; /*< Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_z; /*< Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - uint8_t target_system; /*< System ID.*/ -}) mavlink_set_home_position_t; - -#define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN 53 -#define MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN 53 -#define MAVLINK_MSG_ID_243_LEN 53 -#define MAVLINK_MSG_ID_243_MIN_LEN 53 - -#define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC 85 -#define MAVLINK_MSG_ID_243_CRC 85 - -#define MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \ - 243, \ - "SET_HOME_POSITION", \ - 11, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \ - "SET_HOME_POSITION", \ - 11, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_home_position message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID. - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#else - mavlink_set_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.target_system = target_system; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -} - -/** - * @brief Pack a set_home_position message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID. - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#else - mavlink_set_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.target_system = target_system; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -} - -/** - * @brief Encode a set_home_position struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position) -{ - return mavlink_msg_set_home_position_pack(system_id, component_id, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z); -} - -/** - * @brief Encode a set_home_position struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position) -{ - return mavlink_msg_set_home_position_pack_chan(system_id, component_id, chan, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z); -} - -/** - * @brief Send a set_home_position message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID. - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) - * @param x Local X position of this position in the local coordinate frame - * @param y Local Y position of this position in the local coordinate frame - * @param z Local Z position of this position in the local coordinate frame - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_home_position_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#else - mavlink_set_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.target_system = target_system; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#endif -} - -/** - * @brief Send a set_home_position message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_home_position_send_struct(mavlink_channel_t chan, const mavlink_set_home_position_t* set_home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_home_position_send(chan, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)set_home_position, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#else - mavlink_set_home_position_t *packet = (mavlink_set_home_position_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->x = x; - packet->y = y; - packet->z = z; - packet->approach_x = approach_x; - packet->approach_y = approach_y; - packet->approach_z = approach_z; - packet->target_system = target_system; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_HOME_POSITION UNPACKING - - -/** - * @brief Get field target_system from set_home_position message - * - * @return System ID. - */ -static inline uint8_t mavlink_msg_set_home_position_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field latitude from set_home_position message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_home_position_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from set_home_position message - * - * @return Longitude (WGS84, in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_home_position_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from set_home_position message - * - * @return Altitude (AMSL), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_set_home_position_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field x from set_home_position message - * - * @return Local X position of this position in the local coordinate frame - */ -static inline float mavlink_msg_set_home_position_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field y from set_home_position message - * - * @return Local Y position of this position in the local coordinate frame - */ -static inline float mavlink_msg_set_home_position_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field z from set_home_position message - * - * @return Local Z position of this position in the local coordinate frame - */ -static inline float mavlink_msg_set_home_position_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field q from set_home_position message - * - * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - */ -static inline uint16_t mavlink_msg_set_home_position_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 24); -} - -/** - * @brief Get field approach_x from set_home_position message - * - * @return Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_set_home_position_get_approach_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field approach_y from set_home_position message - * - * @return Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_set_home_position_get_approach_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field approach_z from set_home_position message - * - * @return Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_set_home_position_get_approach_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Decode a set_home_position message into a struct - * - * @param msg The message to decode - * @param set_home_position C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_home_position_decode(const mavlink_message_t* msg, mavlink_set_home_position_t* set_home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_home_position->latitude = mavlink_msg_set_home_position_get_latitude(msg); - set_home_position->longitude = mavlink_msg_set_home_position_get_longitude(msg); - set_home_position->altitude = mavlink_msg_set_home_position_get_altitude(msg); - set_home_position->x = mavlink_msg_set_home_position_get_x(msg); - set_home_position->y = mavlink_msg_set_home_position_get_y(msg); - set_home_position->z = mavlink_msg_set_home_position_get_z(msg); - mavlink_msg_set_home_position_get_q(msg, set_home_position->q); - set_home_position->approach_x = mavlink_msg_set_home_position_get_approach_x(msg); - set_home_position->approach_y = mavlink_msg_set_home_position_get_approach_y(msg); - set_home_position->approach_z = mavlink_msg_set_home_position_get_approach_z(msg); - set_home_position->target_system = mavlink_msg_set_home_position_get_target_system(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_HOME_POSITION_LEN? msg->len : MAVLINK_MSG_ID_SET_HOME_POSITION_LEN; - memset(set_home_position, 0, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); - memcpy(set_home_position, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_set_mode.h b/include/mavlink/v2.0/common/mavlink_msg_set_mode.h deleted file mode 100644 index a4c6ef3..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_set_mode.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE SET_MODE PACKING - -#define MAVLINK_MSG_ID_SET_MODE 11 - -MAVPACKED( -typedef struct __mavlink_set_mode_t { - uint32_t custom_mode; /*< The new autopilot-specific mode. This field can be ignored by an autopilot.*/ - uint8_t target_system; /*< The system setting the mode*/ - uint8_t base_mode; /*< The new base mode*/ -}) mavlink_set_mode_t; - -#define MAVLINK_MSG_ID_SET_MODE_LEN 6 -#define MAVLINK_MSG_ID_SET_MODE_MIN_LEN 6 -#define MAVLINK_MSG_ID_11_LEN 6 -#define MAVLINK_MSG_ID_11_MIN_LEN 6 - -#define MAVLINK_MSG_ID_SET_MODE_CRC 89 -#define MAVLINK_MSG_ID_11_CRC 89 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_MODE { \ - 11, \ - "SET_MODE", \ - 3, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_MODE { \ - "SET_MODE", \ - 3, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_mode message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_MODE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -} - -/** - * @brief Pack a set_mode message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t base_mode,uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -} - -/** - * @brief Encode a set_mode struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_mode C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) -{ - return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); -} - -/** - * @brief Encode a set_mode struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_mode C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_mode_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) -{ - return mavlink_msg_set_mode_pack_chan(system_id, component_id, chan, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); -} - -/** - * @brief Send a set_mode message - * @param chan MAVLink channel to send the message - * - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#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, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#endif -} - -/** - * @brief Send a set_mode message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_mode_send_struct(mavlink_channel_t chan, const mavlink_set_mode_t* set_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_mode_send(chan, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)set_mode, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_MODE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_mode_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#else - mavlink_set_mode_t *packet = (mavlink_set_mode_t *)msgbuf; - 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, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_MODE UNPACKING - - -/** - * @brief Get field target_system from set_mode message - * - * @return The system setting the mode - */ -static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field base_mode from set_mode message - * - * @return The new base mode - */ -static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field custom_mode from set_mode message - * - * @return The new autopilot-specific mode. This field can be ignored by an autopilot. - */ -static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Decode a set_mode message into a struct - * - * @param msg The message to decode - * @param set_mode C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_mode->custom_mode = mavlink_msg_set_mode_get_custom_mode(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_MODE_LEN? msg->len : MAVLINK_MSG_ID_SET_MODE_LEN; - memset(set_mode, 0, MAVLINK_MSG_ID_SET_MODE_LEN); - memcpy(set_mode, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_set_position_target_global_int.h b/include/mavlink/v2.0/common/mavlink_msg_set_position_target_global_int.h deleted file mode 100644 index ec0c9c1..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_set_position_target_global_int.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE SET_POSITION_TARGET_GLOBAL_INT PACKING - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT 86 - -MAVPACKED( -typedef struct __mavlink_set_position_target_global_int_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ - int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/ - int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/ - float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ -}) mavlink_set_position_target_global_int_t; - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53 -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN 53 -#define MAVLINK_MSG_ID_86_LEN 53 -#define MAVLINK_MSG_ID_86_MIN_LEN 53 - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 5 -#define MAVLINK_MSG_ID_86_CRC 5 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \ - 86, \ - "SET_POSITION_TARGET_GLOBAL_INT", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \ - "SET_POSITION_TARGET_GLOBAL_INT", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_position_target_global_int 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_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_set_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Pack a set_position_target_global_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_set_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Encode a set_position_target_global_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ - return mavlink_msg_set_position_target_global_int_pack(system_id, component_id, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); -} - -/** - * @brief Encode a set_position_target_global_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ - return mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, chan, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); -} - -/** - * @brief Send a set_position_target_global_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param lat_int X Position in WGS84 frame in 1e7 * meters - * @param lon_int Y Position in WGS84 frame in 1e7 * meters - * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_set_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -/** - * @brief Send a set_position_target_global_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_position_target_global_int_send_struct(mavlink_channel_t chan, const mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_position_target_global_int_send(chan, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)set_position_target_global_int, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_set_position_target_global_int_t *packet = (mavlink_set_position_target_global_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->lat_int = lat_int; - packet->lon_int = lon_int; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->target_system = target_system; - packet->target_component = target_component; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_POSITION_TARGET_GLOBAL_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from set_position_target_global_int message - * - * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - */ -static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field target_system from set_position_target_global_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field target_component from set_position_target_global_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 51); -} - -/** - * @brief Get field coordinate_frame from set_position_target_global_int message - * - * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - */ -static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field type_mask from set_position_target_global_int message - * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field lat_int from set_position_target_global_int message - * - * @return X Position in WGS84 frame in 1e7 * meters - */ -static inline int32_t mavlink_msg_set_position_target_global_int_get_lat_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon_int from set_position_target_global_int message - * - * @return Y Position in WGS84 frame in 1e7 * meters - */ -static inline int32_t mavlink_msg_set_position_target_global_int_get_lon_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt from set_position_target_global_int message - * - * @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - */ -static inline float mavlink_msg_set_position_target_global_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from set_position_target_global_int message - * - * @return X velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_global_int_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from set_position_target_global_int message - * - * @return Y velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_global_int_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from set_position_target_global_int message - * - * @return Z velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_global_int_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from set_position_target_global_int message - * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_global_int_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from set_position_target_global_int message - * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_global_int_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from set_position_target_global_int message - * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_global_int_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from set_position_target_global_int message - * - * @return yaw setpoint in rad - */ -static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from set_position_target_global_int message - * - * @return yaw rate setpoint in rad/s - */ -static inline float mavlink_msg_set_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a set_position_target_global_int message into a struct - * - * @param msg The message to decode - * @param set_position_target_global_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_position_target_global_int->time_boot_ms = mavlink_msg_set_position_target_global_int_get_time_boot_ms(msg); - set_position_target_global_int->lat_int = mavlink_msg_set_position_target_global_int_get_lat_int(msg); - set_position_target_global_int->lon_int = mavlink_msg_set_position_target_global_int_get_lon_int(msg); - set_position_target_global_int->alt = mavlink_msg_set_position_target_global_int_get_alt(msg); - set_position_target_global_int->vx = mavlink_msg_set_position_target_global_int_get_vx(msg); - set_position_target_global_int->vy = mavlink_msg_set_position_target_global_int_get_vy(msg); - set_position_target_global_int->vz = mavlink_msg_set_position_target_global_int_get_vz(msg); - set_position_target_global_int->afx = mavlink_msg_set_position_target_global_int_get_afx(msg); - set_position_target_global_int->afy = mavlink_msg_set_position_target_global_int_get_afy(msg); - set_position_target_global_int->afz = mavlink_msg_set_position_target_global_int_get_afz(msg); - set_position_target_global_int->yaw = mavlink_msg_set_position_target_global_int_get_yaw(msg); - set_position_target_global_int->yaw_rate = mavlink_msg_set_position_target_global_int_get_yaw_rate(msg); - set_position_target_global_int->type_mask = mavlink_msg_set_position_target_global_int_get_type_mask(msg); - set_position_target_global_int->target_system = mavlink_msg_set_position_target_global_int_get_target_system(msg); - set_position_target_global_int->target_component = mavlink_msg_set_position_target_global_int_get_target_component(msg); - set_position_target_global_int->coordinate_frame = mavlink_msg_set_position_target_global_int_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN? msg->len : MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN; - memset(set_position_target_global_int, 0, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); - memcpy(set_position_target_global_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_set_position_target_local_ned.h b/include/mavlink/v2.0/common/mavlink_msg_set_position_target_local_ned.h deleted file mode 100644 index af4e8d6..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_set_position_target_local_ned.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE SET_POSITION_TARGET_LOCAL_NED PACKING - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED 84 - -MAVPACKED( -typedef struct __mavlink_set_position_target_local_ned_t { - uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ - float x; /*< X Position in NED frame in meters*/ - float y; /*< Y Position in NED frame in meters*/ - float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/ - float vx; /*< X velocity in NED frame in meter / s*/ - float vy; /*< Y velocity in NED frame in meter / s*/ - float vz; /*< Z velocity in NED frame in meter / s*/ - float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< yaw setpoint in rad*/ - float yaw_rate; /*< yaw rate setpoint in rad/s*/ - uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ -}) mavlink_set_position_target_local_ned_t; - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53 -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN 53 -#define MAVLINK_MSG_ID_84_LEN 53 -#define MAVLINK_MSG_ID_84_MIN_LEN 53 - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 143 -#define MAVLINK_MSG_ID_84_CRC 143 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \ - 84, \ - "SET_POSITION_TARGET_LOCAL_NED", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \ - "SET_POSITION_TARGET_LOCAL_NED", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_position_target_local_ned 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_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_set_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Pack a set_position_target_local_ned message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_set_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Encode a set_position_target_local_ned struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ - return mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); -} - -/** - * @brief Encode a set_position_target_local_ned struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ - return mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); -} - -/** - * @brief Send a set_position_target_local_ned message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - * @param x X Position in NED frame in meters - * @param y Y Position in NED frame in meters - * @param z Z Position in NED frame in meters (note, altitude is negative in NED) - * @param vx X velocity in NED frame in meter / s - * @param vy Y velocity in NED frame in meter / s - * @param vz Z velocity in NED frame in meter / s - * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw yaw setpoint in rad - * @param yaw_rate yaw rate setpoint in rad/s - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_set_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -/** - * @brief Send a set_position_target_local_ned message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_position_target_local_ned_send_struct(mavlink_channel_t chan, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_position_target_local_ned_send(chan, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)set_position_target_local_ned, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_set_position_target_local_ned_t *packet = (mavlink_set_position_target_local_ned_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->target_system = target_system; - packet->target_component = target_component; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_POSITION_TARGET_LOCAL_NED UNPACKING - - -/** - * @brief Get field time_boot_ms from set_position_target_local_ned message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_set_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field target_system from set_position_target_local_ned message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field target_component from set_position_target_local_ned message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 51); -} - -/** - * @brief Get field coordinate_frame from set_position_target_local_ned message - * - * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - */ -static inline uint8_t mavlink_msg_set_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field type_mask from set_position_target_local_ned message - * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field x from set_position_target_local_ned message - * - * @return X Position in NED frame in meters - */ -static inline float mavlink_msg_set_position_target_local_ned_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from set_position_target_local_ned message - * - * @return Y Position in NED frame in meters - */ -static inline float mavlink_msg_set_position_target_local_ned_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from set_position_target_local_ned message - * - * @return Z Position in NED frame in meters (note, altitude is negative in NED) - */ -static inline float mavlink_msg_set_position_target_local_ned_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from set_position_target_local_ned message - * - * @return X velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_local_ned_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from set_position_target_local_ned message - * - * @return Y velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_local_ned_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from set_position_target_local_ned message - * - * @return Z velocity in NED frame in meter / s - */ -static inline float mavlink_msg_set_position_target_local_ned_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from set_position_target_local_ned message - * - * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_local_ned_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from set_position_target_local_ned message - * - * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_local_ned_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from set_position_target_local_ned message - * - * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_local_ned_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from set_position_target_local_ned message - * - * @return yaw setpoint in rad - */ -static inline float mavlink_msg_set_position_target_local_ned_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from set_position_target_local_ned message - * - * @return yaw rate setpoint in rad/s - */ -static inline float mavlink_msg_set_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a set_position_target_local_ned message into a struct - * - * @param msg The message to decode - * @param set_position_target_local_ned C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_position_target_local_ned->time_boot_ms = mavlink_msg_set_position_target_local_ned_get_time_boot_ms(msg); - set_position_target_local_ned->x = mavlink_msg_set_position_target_local_ned_get_x(msg); - set_position_target_local_ned->y = mavlink_msg_set_position_target_local_ned_get_y(msg); - set_position_target_local_ned->z = mavlink_msg_set_position_target_local_ned_get_z(msg); - set_position_target_local_ned->vx = mavlink_msg_set_position_target_local_ned_get_vx(msg); - set_position_target_local_ned->vy = mavlink_msg_set_position_target_local_ned_get_vy(msg); - set_position_target_local_ned->vz = mavlink_msg_set_position_target_local_ned_get_vz(msg); - set_position_target_local_ned->afx = mavlink_msg_set_position_target_local_ned_get_afx(msg); - set_position_target_local_ned->afy = mavlink_msg_set_position_target_local_ned_get_afy(msg); - set_position_target_local_ned->afz = mavlink_msg_set_position_target_local_ned_get_afz(msg); - set_position_target_local_ned->yaw = mavlink_msg_set_position_target_local_ned_get_yaw(msg); - set_position_target_local_ned->yaw_rate = mavlink_msg_set_position_target_local_ned_get_yaw_rate(msg); - set_position_target_local_ned->type_mask = mavlink_msg_set_position_target_local_ned_get_type_mask(msg); - set_position_target_local_ned->target_system = mavlink_msg_set_position_target_local_ned_get_target_system(msg); - set_position_target_local_ned->target_component = mavlink_msg_set_position_target_local_ned_get_target_component(msg); - set_position_target_local_ned->coordinate_frame = mavlink_msg_set_position_target_local_ned_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN? msg->len : MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN; - memset(set_position_target_local_ned, 0, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); - memcpy(set_position_target_local_ned, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_set_video_stream_settings.h b/include/mavlink/v2.0/common/mavlink_msg_set_video_stream_settings.h deleted file mode 100644 index 051929b..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_set_video_stream_settings.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE SET_VIDEO_STREAM_SETTINGS PACKING - -#define MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS 270 - -MAVPACKED( -typedef struct __mavlink_set_video_stream_settings_t { - float framerate; /*< Frames per second (set to -1 for highest framerate possible)*/ - uint32_t bitrate; /*< Bit rate in bits per second (set to -1 for auto)*/ - uint16_t resolution_h; /*< Resolution horizontal in pixels (set to -1 for highest resolution possible)*/ - uint16_t resolution_v; /*< Resolution vertical in pixels (set to -1 for highest resolution possible)*/ - uint16_t rotation; /*< Video image rotation clockwise (0-359 degrees)*/ - uint8_t target_system; /*< system ID of the target*/ - uint8_t target_component; /*< component ID of the target*/ - uint8_t camera_id; /*< Camera ID (1 for first, 2 for second, etc.)*/ - char uri[230]; /*< Video stream URI*/ -}) mavlink_set_video_stream_settings_t; - -#define MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN 247 -#define MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_MIN_LEN 247 -#define MAVLINK_MSG_ID_270_LEN 247 -#define MAVLINK_MSG_ID_270_MIN_LEN 247 - -#define MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_CRC 232 -#define MAVLINK_MSG_ID_270_CRC 232 - -#define MAVLINK_MSG_SET_VIDEO_STREAM_SETTINGS_FIELD_URI_LEN 230 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_VIDEO_STREAM_SETTINGS { \ - 270, \ - "SET_VIDEO_STREAM_SETTINGS", \ - 9, \ - { { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_video_stream_settings_t, framerate) }, \ - { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_set_video_stream_settings_t, bitrate) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_set_video_stream_settings_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_set_video_stream_settings_t, resolution_v) }, \ - { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_set_video_stream_settings_t, rotation) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_set_video_stream_settings_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_set_video_stream_settings_t, target_component) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_video_stream_settings_t, camera_id) }, \ - { "uri", NULL, MAVLINK_TYPE_CHAR, 230, 17, offsetof(mavlink_set_video_stream_settings_t, uri) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_VIDEO_STREAM_SETTINGS { \ - "SET_VIDEO_STREAM_SETTINGS", \ - 9, \ - { { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_video_stream_settings_t, framerate) }, \ - { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_set_video_stream_settings_t, bitrate) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_set_video_stream_settings_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_set_video_stream_settings_t, resolution_v) }, \ - { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_set_video_stream_settings_t, rotation) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_set_video_stream_settings_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_set_video_stream_settings_t, target_component) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_video_stream_settings_t, camera_id) }, \ - { "uri", NULL, MAVLINK_TYPE_CHAR, 230, 17, offsetof(mavlink_set_video_stream_settings_t, uri) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_video_stream_settings message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param camera_id Camera ID (1 for first, 2 for second, etc.) - * @param framerate Frames per second (set to -1 for highest framerate possible) - * @param resolution_h Resolution horizontal in pixels (set to -1 for highest resolution possible) - * @param resolution_v Resolution vertical in pixels (set to -1 for highest resolution possible) - * @param bitrate Bit rate in bits per second (set to -1 for auto) - * @param rotation Video image rotation clockwise (0-359 degrees) - * @param uri Video stream URI - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_video_stream_settings_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t camera_id, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, resolution_h); - _mav_put_uint16_t(buf, 10, resolution_v); - _mav_put_uint16_t(buf, 12, rotation); - _mav_put_uint8_t(buf, 14, target_system); - _mav_put_uint8_t(buf, 15, target_component); - _mav_put_uint8_t(buf, 16, camera_id); - _mav_put_char_array(buf, 17, uri, 230); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN); -#else - mavlink_set_video_stream_settings_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.target_system = target_system; - packet.target_component = target_component; - packet.camera_id = camera_id; - mav_array_memcpy(packet.uri, uri, sizeof(char)*230); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_CRC); -} - -/** - * @brief Pack a set_video_stream_settings message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param camera_id Camera ID (1 for first, 2 for second, etc.) - * @param framerate Frames per second (set to -1 for highest framerate possible) - * @param resolution_h Resolution horizontal in pixels (set to -1 for highest resolution possible) - * @param resolution_v Resolution vertical in pixels (set to -1 for highest resolution possible) - * @param bitrate Bit rate in bits per second (set to -1 for auto) - * @param rotation Video image rotation clockwise (0-359 degrees) - * @param uri Video stream URI - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_video_stream_settings_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t camera_id,float framerate,uint16_t resolution_h,uint16_t resolution_v,uint32_t bitrate,uint16_t rotation,const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, resolution_h); - _mav_put_uint16_t(buf, 10, resolution_v); - _mav_put_uint16_t(buf, 12, rotation); - _mav_put_uint8_t(buf, 14, target_system); - _mav_put_uint8_t(buf, 15, target_component); - _mav_put_uint8_t(buf, 16, camera_id); - _mav_put_char_array(buf, 17, uri, 230); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN); -#else - mavlink_set_video_stream_settings_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.target_system = target_system; - packet.target_component = target_component; - packet.camera_id = camera_id; - mav_array_memcpy(packet.uri, uri, sizeof(char)*230); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_CRC); -} - -/** - * @brief Encode a set_video_stream_settings struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_video_stream_settings C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_video_stream_settings_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_video_stream_settings_t* set_video_stream_settings) -{ - return mavlink_msg_set_video_stream_settings_pack(system_id, component_id, msg, set_video_stream_settings->target_system, set_video_stream_settings->target_component, set_video_stream_settings->camera_id, set_video_stream_settings->framerate, set_video_stream_settings->resolution_h, set_video_stream_settings->resolution_v, set_video_stream_settings->bitrate, set_video_stream_settings->rotation, set_video_stream_settings->uri); -} - -/** - * @brief Encode a set_video_stream_settings struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_video_stream_settings C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_video_stream_settings_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_video_stream_settings_t* set_video_stream_settings) -{ - return mavlink_msg_set_video_stream_settings_pack_chan(system_id, component_id, chan, msg, set_video_stream_settings->target_system, set_video_stream_settings->target_component, set_video_stream_settings->camera_id, set_video_stream_settings->framerate, set_video_stream_settings->resolution_h, set_video_stream_settings->resolution_v, set_video_stream_settings->bitrate, set_video_stream_settings->rotation, set_video_stream_settings->uri); -} - -/** - * @brief Send a set_video_stream_settings message - * @param chan MAVLink channel to send the message - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param camera_id Camera ID (1 for first, 2 for second, etc.) - * @param framerate Frames per second (set to -1 for highest framerate possible) - * @param resolution_h Resolution horizontal in pixels (set to -1 for highest resolution possible) - * @param resolution_v Resolution vertical in pixels (set to -1 for highest resolution possible) - * @param bitrate Bit rate in bits per second (set to -1 for auto) - * @param rotation Video image rotation clockwise (0-359 degrees) - * @param uri Video stream URI - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_video_stream_settings_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t camera_id, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, resolution_h); - _mav_put_uint16_t(buf, 10, resolution_v); - _mav_put_uint16_t(buf, 12, rotation); - _mav_put_uint8_t(buf, 14, target_system); - _mav_put_uint8_t(buf, 15, target_component); - _mav_put_uint8_t(buf, 16, camera_id); - _mav_put_char_array(buf, 17, uri, 230); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS, buf, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_CRC); -#else - mavlink_set_video_stream_settings_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.target_system = target_system; - packet.target_component = target_component; - packet.camera_id = camera_id; - mav_array_memcpy(packet.uri, uri, sizeof(char)*230); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS, (const char *)&packet, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_CRC); -#endif -} - -/** - * @brief Send a set_video_stream_settings message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_video_stream_settings_send_struct(mavlink_channel_t chan, const mavlink_set_video_stream_settings_t* set_video_stream_settings) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_video_stream_settings_send(chan, set_video_stream_settings->target_system, set_video_stream_settings->target_component, set_video_stream_settings->camera_id, set_video_stream_settings->framerate, set_video_stream_settings->resolution_h, set_video_stream_settings->resolution_v, set_video_stream_settings->bitrate, set_video_stream_settings->rotation, set_video_stream_settings->uri); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS, (const char *)set_video_stream_settings, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_video_stream_settings_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t camera_id, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, resolution_h); - _mav_put_uint16_t(buf, 10, resolution_v); - _mav_put_uint16_t(buf, 12, rotation); - _mav_put_uint8_t(buf, 14, target_system); - _mav_put_uint8_t(buf, 15, target_component); - _mav_put_uint8_t(buf, 16, camera_id); - _mav_put_char_array(buf, 17, uri, 230); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS, buf, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_CRC); -#else - mavlink_set_video_stream_settings_t *packet = (mavlink_set_video_stream_settings_t *)msgbuf; - packet->framerate = framerate; - packet->bitrate = bitrate; - packet->resolution_h = resolution_h; - packet->resolution_v = resolution_v; - packet->rotation = rotation; - packet->target_system = target_system; - packet->target_component = target_component; - packet->camera_id = camera_id; - mav_array_memcpy(packet->uri, uri, sizeof(char)*230); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS, (const char *)packet, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_VIDEO_STREAM_SETTINGS UNPACKING - - -/** - * @brief Get field target_system from set_video_stream_settings message - * - * @return system ID of the target - */ -static inline uint8_t mavlink_msg_set_video_stream_settings_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 14); -} - -/** - * @brief Get field target_component from set_video_stream_settings message - * - * @return component ID of the target - */ -static inline uint8_t mavlink_msg_set_video_stream_settings_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 15); -} - -/** - * @brief Get field camera_id from set_video_stream_settings message - * - * @return Camera ID (1 for first, 2 for second, etc.) - */ -static inline uint8_t mavlink_msg_set_video_stream_settings_get_camera_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field framerate from set_video_stream_settings message - * - * @return Frames per second (set to -1 for highest framerate possible) - */ -static inline float mavlink_msg_set_video_stream_settings_get_framerate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field resolution_h from set_video_stream_settings message - * - * @return Resolution horizontal in pixels (set to -1 for highest resolution possible) - */ -static inline uint16_t mavlink_msg_set_video_stream_settings_get_resolution_h(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field resolution_v from set_video_stream_settings message - * - * @return Resolution vertical in pixels (set to -1 for highest resolution possible) - */ -static inline uint16_t mavlink_msg_set_video_stream_settings_get_resolution_v(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field bitrate from set_video_stream_settings message - * - * @return Bit rate in bits per second (set to -1 for auto) - */ -static inline uint32_t mavlink_msg_set_video_stream_settings_get_bitrate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field rotation from set_video_stream_settings message - * - * @return Video image rotation clockwise (0-359 degrees) - */ -static inline uint16_t mavlink_msg_set_video_stream_settings_get_rotation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field uri from set_video_stream_settings message - * - * @return Video stream URI - */ -static inline uint16_t mavlink_msg_set_video_stream_settings_get_uri(const mavlink_message_t* msg, char *uri) -{ - return _MAV_RETURN_char_array(msg, uri, 230, 17); -} - -/** - * @brief Decode a set_video_stream_settings message into a struct - * - * @param msg The message to decode - * @param set_video_stream_settings C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_video_stream_settings_decode(const mavlink_message_t* msg, mavlink_set_video_stream_settings_t* set_video_stream_settings) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_video_stream_settings->framerate = mavlink_msg_set_video_stream_settings_get_framerate(msg); - set_video_stream_settings->bitrate = mavlink_msg_set_video_stream_settings_get_bitrate(msg); - set_video_stream_settings->resolution_h = mavlink_msg_set_video_stream_settings_get_resolution_h(msg); - set_video_stream_settings->resolution_v = mavlink_msg_set_video_stream_settings_get_resolution_v(msg); - set_video_stream_settings->rotation = mavlink_msg_set_video_stream_settings_get_rotation(msg); - set_video_stream_settings->target_system = mavlink_msg_set_video_stream_settings_get_target_system(msg); - set_video_stream_settings->target_component = mavlink_msg_set_video_stream_settings_get_target_component(msg); - set_video_stream_settings->camera_id = mavlink_msg_set_video_stream_settings_get_camera_id(msg); - mavlink_msg_set_video_stream_settings_get_uri(msg, set_video_stream_settings->uri); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN? msg->len : MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN; - memset(set_video_stream_settings, 0, MAVLINK_MSG_ID_SET_VIDEO_STREAM_SETTINGS_LEN); - memcpy(set_video_stream_settings, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_setup_signing.h b/include/mavlink/v2.0/common/mavlink_msg_setup_signing.h deleted file mode 100644 index 5ba8d0f..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_setup_signing.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE SETUP_SIGNING PACKING - -#define MAVLINK_MSG_ID_SETUP_SIGNING 256 - -MAVPACKED( -typedef struct __mavlink_setup_signing_t { - uint64_t initial_timestamp; /*< initial timestamp*/ - uint8_t target_system; /*< system id of the target*/ - uint8_t target_component; /*< component ID of the target*/ - uint8_t secret_key[32]; /*< signing key*/ -}) mavlink_setup_signing_t; - -#define MAVLINK_MSG_ID_SETUP_SIGNING_LEN 42 -#define MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN 42 -#define MAVLINK_MSG_ID_256_LEN 42 -#define MAVLINK_MSG_ID_256_MIN_LEN 42 - -#define MAVLINK_MSG_ID_SETUP_SIGNING_CRC 71 -#define MAVLINK_MSG_ID_256_CRC 71 - -#define MAVLINK_MSG_SETUP_SIGNING_FIELD_SECRET_KEY_LEN 32 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SETUP_SIGNING { \ - 256, \ - "SETUP_SIGNING", \ - 4, \ - { { "initial_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_setup_signing_t, initial_timestamp) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_setup_signing_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_setup_signing_t, target_component) }, \ - { "secret_key", NULL, MAVLINK_TYPE_UINT8_T, 32, 10, offsetof(mavlink_setup_signing_t, secret_key) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SETUP_SIGNING { \ - "SETUP_SIGNING", \ - 4, \ - { { "initial_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_setup_signing_t, initial_timestamp) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_setup_signing_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_setup_signing_t, target_component) }, \ - { "secret_key", NULL, MAVLINK_TYPE_UINT8_T, 32, 10, offsetof(mavlink_setup_signing_t, secret_key) }, \ - } \ -} -#endif - -/** - * @brief Pack a setup_signing message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system system id of the target - * @param target_component component ID of the target - * @param secret_key signing key - * @param initial_timestamp initial timestamp - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_setup_signing_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const uint8_t *secret_key, uint64_t initial_timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETUP_SIGNING_LEN]; - _mav_put_uint64_t(buf, 0, initial_timestamp); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t_array(buf, 10, secret_key, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETUP_SIGNING_LEN); -#else - mavlink_setup_signing_t packet; - packet.initial_timestamp = initial_timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.secret_key, secret_key, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETUP_SIGNING_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SETUP_SIGNING; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -} - -/** - * @brief Pack a setup_signing message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system system id of the target - * @param target_component component ID of the target - * @param secret_key signing key - * @param initial_timestamp initial timestamp - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_setup_signing_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const uint8_t *secret_key,uint64_t initial_timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETUP_SIGNING_LEN]; - _mav_put_uint64_t(buf, 0, initial_timestamp); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t_array(buf, 10, secret_key, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETUP_SIGNING_LEN); -#else - mavlink_setup_signing_t packet; - packet.initial_timestamp = initial_timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.secret_key, secret_key, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETUP_SIGNING_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SETUP_SIGNING; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -} - -/** - * @brief Encode a setup_signing struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param setup_signing C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_setup_signing_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_setup_signing_t* setup_signing) -{ - return mavlink_msg_setup_signing_pack(system_id, component_id, msg, setup_signing->target_system, setup_signing->target_component, setup_signing->secret_key, setup_signing->initial_timestamp); -} - -/** - * @brief Encode a setup_signing struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param setup_signing C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_setup_signing_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_setup_signing_t* setup_signing) -{ - return mavlink_msg_setup_signing_pack_chan(system_id, component_id, chan, msg, setup_signing->target_system, setup_signing->target_component, setup_signing->secret_key, setup_signing->initial_timestamp); -} - -/** - * @brief Send a setup_signing message - * @param chan MAVLink channel to send the message - * - * @param target_system system id of the target - * @param target_component component ID of the target - * @param secret_key signing key - * @param initial_timestamp initial timestamp - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_setup_signing_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *secret_key, uint64_t initial_timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETUP_SIGNING_LEN]; - _mav_put_uint64_t(buf, 0, initial_timestamp); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t_array(buf, 10, secret_key, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETUP_SIGNING, buf, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -#else - mavlink_setup_signing_t packet; - packet.initial_timestamp = initial_timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.secret_key, secret_key, sizeof(uint8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETUP_SIGNING, (const char *)&packet, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -#endif -} - -/** - * @brief Send a setup_signing message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_setup_signing_send_struct(mavlink_channel_t chan, const mavlink_setup_signing_t* setup_signing) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_setup_signing_send(chan, setup_signing->target_system, setup_signing->target_component, setup_signing->secret_key, setup_signing->initial_timestamp); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETUP_SIGNING, (const char *)setup_signing, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SETUP_SIGNING_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_setup_signing_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *secret_key, uint64_t initial_timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, initial_timestamp); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t_array(buf, 10, secret_key, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETUP_SIGNING, buf, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -#else - mavlink_setup_signing_t *packet = (mavlink_setup_signing_t *)msgbuf; - packet->initial_timestamp = initial_timestamp; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->secret_key, secret_key, sizeof(uint8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETUP_SIGNING, (const char *)packet, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SETUP_SIGNING UNPACKING - - -/** - * @brief Get field target_system from setup_signing message - * - * @return system id of the target - */ -static inline uint8_t mavlink_msg_setup_signing_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field target_component from setup_signing message - * - * @return component ID of the target - */ -static inline uint8_t mavlink_msg_setup_signing_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 9); -} - -/** - * @brief Get field secret_key from setup_signing message - * - * @return signing key - */ -static inline uint16_t mavlink_msg_setup_signing_get_secret_key(const mavlink_message_t* msg, uint8_t *secret_key) -{ - return _MAV_RETURN_uint8_t_array(msg, secret_key, 32, 10); -} - -/** - * @brief Get field initial_timestamp from setup_signing message - * - * @return initial timestamp - */ -static inline uint64_t mavlink_msg_setup_signing_get_initial_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Decode a setup_signing message into a struct - * - * @param msg The message to decode - * @param setup_signing C-struct to decode the message contents into - */ -static inline void mavlink_msg_setup_signing_decode(const mavlink_message_t* msg, mavlink_setup_signing_t* setup_signing) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - setup_signing->initial_timestamp = mavlink_msg_setup_signing_get_initial_timestamp(msg); - setup_signing->target_system = mavlink_msg_setup_signing_get_target_system(msg); - setup_signing->target_component = mavlink_msg_setup_signing_get_target_component(msg); - mavlink_msg_setup_signing_get_secret_key(msg, setup_signing->secret_key); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SETUP_SIGNING_LEN? msg->len : MAVLINK_MSG_ID_SETUP_SIGNING_LEN; - memset(setup_signing, 0, MAVLINK_MSG_ID_SETUP_SIGNING_LEN); - memcpy(setup_signing, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_sim_state.h b/include/mavlink/v2.0/common/mavlink_msg_sim_state.h deleted file mode 100644 index e49a07f..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_sim_state.h +++ /dev/null @@ -1,713 +0,0 @@ -#pragma once -// MESSAGE SIM_STATE PACKING - -#define MAVLINK_MSG_ID_SIM_STATE 108 - -MAVPACKED( -typedef struct __mavlink_sim_state_t { - float q1; /*< True attitude quaternion component 1, w (1 in null-rotation)*/ - float q2; /*< True attitude quaternion component 2, x (0 in null-rotation)*/ - float q3; /*< True attitude quaternion component 3, y (0 in null-rotation)*/ - float q4; /*< True attitude quaternion component 4, z (0 in null-rotation)*/ - float roll; /*< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs*/ - float pitch; /*< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs*/ - float yaw; /*< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs*/ - float xacc; /*< X acceleration m/s/s*/ - float yacc; /*< Y acceleration m/s/s*/ - float zacc; /*< Z acceleration m/s/s*/ - float xgyro; /*< Angular speed around X axis rad/s*/ - float ygyro; /*< Angular speed around Y axis rad/s*/ - float zgyro; /*< Angular speed around Z axis rad/s*/ - float lat; /*< Latitude in degrees*/ - float lon; /*< Longitude in degrees*/ - float alt; /*< Altitude in meters*/ - float std_dev_horz; /*< Horizontal position standard deviation*/ - float std_dev_vert; /*< Vertical position standard deviation*/ - float vn; /*< True velocity in m/s in NORTH direction in earth-fixed NED frame*/ - float ve; /*< True velocity in m/s in EAST direction in earth-fixed NED frame*/ - float vd; /*< True velocity in m/s in DOWN direction in earth-fixed NED frame*/ -}) mavlink_sim_state_t; - -#define MAVLINK_MSG_ID_SIM_STATE_LEN 84 -#define MAVLINK_MSG_ID_SIM_STATE_MIN_LEN 84 -#define MAVLINK_MSG_ID_108_LEN 84 -#define MAVLINK_MSG_ID_108_MIN_LEN 84 - -#define MAVLINK_MSG_ID_SIM_STATE_CRC 32 -#define MAVLINK_MSG_ID_108_CRC 32 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SIM_STATE { \ - 108, \ - "SIM_STATE", \ - 21, \ - { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \ - { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \ - { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \ - { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SIM_STATE { \ - "SIM_STATE", \ - 21, \ - { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \ - { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \ - { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \ - { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \ - } \ -} -#endif - -/** - * @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 q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame - * @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 q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _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, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - 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.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SIM_STATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -} - -/** - * @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 will be sent over - * @param msg The MAVLink message to compress the data into - * @param q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame - * @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 q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _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, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - 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.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SIM_STATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -} - -/** - * @brief Encode a sim_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param 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->q1, sim_state->q2, sim_state->q3, sim_state->q4, 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->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); -} - -/** - * @brief Encode a sim_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sim_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sim_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state) -{ - return mavlink_msg_sim_state_pack_chan(system_id, component_id, chan, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, 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->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); -} - -/** - * @brief Send a sim_state message - * @param chan MAVLink channel to send the message - * - * @param q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_sim_state_send(mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _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, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - 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.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#endif -} - -/** - * @brief Send a sim_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_sim_state_send_struct(mavlink_channel_t chan, const mavlink_sim_state_t* sim_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_sim_state_send(chan, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, 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->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)sim_state, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SIM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_sim_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _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, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - mavlink_sim_state_t *packet = (mavlink_sim_state_t *)msgbuf; - packet->q1 = q1; - packet->q2 = q2; - packet->q3 = q3; - packet->q4 = q4; - 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->lon = lon; - packet->alt = alt; - packet->std_dev_horz = std_dev_horz; - packet->std_dev_vert = std_dev_vert; - packet->vn = vn; - packet->ve = ve; - packet->vd = vd; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SIM_STATE UNPACKING - - -/** - * @brief Get field q1 from sim_state message - * - * @return True attitude quaternion component 1, w (1 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field q2 from sim_state message - * - * @return True attitude quaternion component 2, x (0 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field q3 from sim_state message - * - * @return True attitude quaternion component 3, y (0 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field q4 from sim_state message - * - * @return True attitude quaternion component 4, z (0 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field roll from sim_state message - * - * @return Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitch from sim_state message - * - * @return Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yaw from sim_state message - * - * @return Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @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, 28); -} - -/** - * @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, 32); -} - -/** - * @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, 36); -} - -/** - * @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, 40); -} - -/** - * @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, 44); -} - -/** - * @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, 48); -} - -/** - * @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, 52); -} - -/** - * @brief Get field lon from sim_state message - * - * @return Longitude in degrees - */ -static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field alt from sim_state message - * - * @return Altitude in meters - */ -static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 60); -} - -/** - * @brief Get field std_dev_horz from sim_state message - * - * @return Horizontal position standard deviation - */ -static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 64); -} - -/** - * @brief Get field std_dev_vert from sim_state message - * - * @return Vertical position standard deviation - */ -static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 68); -} - -/** - * @brief Get field vn from sim_state message - * - * @return True velocity in m/s in NORTH direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 72); -} - -/** - * @brief Get field ve from sim_state message - * - * @return True velocity in m/s in EAST direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 76); -} - -/** - * @brief Get field vd from sim_state message - * - * @return True velocity in m/s in DOWN direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_vd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 80); -} - -/** - * @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 || !MAVLINK_ALIGNED_FIELDS - sim_state->q1 = mavlink_msg_sim_state_get_q1(msg); - sim_state->q2 = mavlink_msg_sim_state_get_q2(msg); - sim_state->q3 = mavlink_msg_sim_state_get_q3(msg); - sim_state->q4 = mavlink_msg_sim_state_get_q4(msg); - 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->lon = mavlink_msg_sim_state_get_lon(msg); - sim_state->alt = mavlink_msg_sim_state_get_alt(msg); - sim_state->std_dev_horz = mavlink_msg_sim_state_get_std_dev_horz(msg); - sim_state->std_dev_vert = mavlink_msg_sim_state_get_std_dev_vert(msg); - sim_state->vn = mavlink_msg_sim_state_get_vn(msg); - sim_state->ve = mavlink_msg_sim_state_get_ve(msg); - sim_state->vd = mavlink_msg_sim_state_get_vd(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SIM_STATE_LEN? msg->len : MAVLINK_MSG_ID_SIM_STATE_LEN; - memset(sim_state, 0, MAVLINK_MSG_ID_SIM_STATE_LEN); - memcpy(sim_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_statustext.h b/include/mavlink/v2.0/common/mavlink_msg_statustext.h deleted file mode 100644 index e1ed320..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_statustext.h +++ /dev/null @@ -1,230 +0,0 @@ -#pragma once -// MESSAGE STATUSTEXT PACKING - -#define MAVLINK_MSG_ID_STATUSTEXT 253 - -MAVPACKED( -typedef struct __mavlink_statustext_t { - uint8_t severity; /*< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.*/ - char text[50]; /*< Status text message, without null termination character*/ -}) mavlink_statustext_t; - -#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51 -#define MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN 51 -#define MAVLINK_MSG_ID_253_LEN 51 -#define MAVLINK_MSG_ID_253_MIN_LEN 51 - -#define MAVLINK_MSG_ID_STATUSTEXT_CRC 83 -#define MAVLINK_MSG_ID_253_CRC 83 - -#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ - 253, \ - "STATUSTEXT", \ - 2, \ - { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ - { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ - "STATUSTEXT", \ - 2, \ - { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ - { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \ - } \ -} -#endif - -/** - * @brief Pack a statustext 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 severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t severity, const char *text) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -} - -/** - * @brief Pack a statustext message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t severity,const char *text) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -} - -/** - * @brief Encode a statustext struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param statustext C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext) -{ - return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text); -} - -/** - * @brief Encode a statustext struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param statustext C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_statustext_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_statustext_t* statustext) -{ - return mavlink_msg_statustext_pack_chan(system_id, component_id, chan, msg, statustext->severity, statustext->text); -} - -/** - * @brief Send a statustext message - * @param chan MAVLink channel to send the message - * - * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#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, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#endif -} - -/** - * @brief Send a statustext message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_statustext_send_struct(mavlink_channel_t chan, const mavlink_statustext_t* statustext) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_statustext_send(chan, statustext->severity, statustext->text); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)statustext, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_STATUSTEXT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_statustext_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t severity, const char *text) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#else - mavlink_statustext_t *packet = (mavlink_statustext_t *)msgbuf; - 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, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE STATUSTEXT UNPACKING - - -/** - * @brief Get field severity from statustext message - * - * @return Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - */ -static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field text from statustext message - * - * @return Status text message, without null termination character - */ -static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text) -{ - return _MAV_RETURN_char_array(msg, text, 50, 1); -} - -/** - * @brief Decode a statustext message into a struct - * - * @param msg The message to decode - * @param statustext C-struct to decode the message contents into - */ -static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - statustext->severity = mavlink_msg_statustext_get_severity(msg); - mavlink_msg_statustext_get_text(msg, statustext->text); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_STATUSTEXT_LEN? msg->len : MAVLINK_MSG_ID_STATUSTEXT_LEN; - memset(statustext, 0, MAVLINK_MSG_ID_STATUSTEXT_LEN); - memcpy(statustext, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_storage_information.h b/include/mavlink/v2.0/common/mavlink_msg_storage_information.h deleted file mode 100644 index 1837689..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_storage_information.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE STORAGE_INFORMATION PACKING - -#define MAVLINK_MSG_ID_STORAGE_INFORMATION 261 - -MAVPACKED( -typedef struct __mavlink_storage_information_t { - uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ - float total_capacity; /*< Total capacity in MiB*/ - float used_capacity; /*< Used capacity in MiB*/ - float available_capacity; /*< Available capacity in MiB*/ - float read_speed; /*< Read speed in MiB/s*/ - float write_speed; /*< Write speed in MiB/s*/ - uint8_t storage_id; /*< Storage ID if there are multiple*/ - uint8_t status; /*< Status of storage (0 not available, 1 unformatted, 2 formatted)*/ -}) mavlink_storage_information_t; - -#define MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN 26 -#define MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN 26 -#define MAVLINK_MSG_ID_261_LEN 26 -#define MAVLINK_MSG_ID_261_MIN_LEN 26 - -#define MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC 244 -#define MAVLINK_MSG_ID_261_CRC 244 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION { \ - 261, \ - "STORAGE_INFORMATION", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_storage_information_t, time_boot_ms) }, \ - { "total_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_storage_information_t, total_capacity) }, \ - { "used_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_storage_information_t, used_capacity) }, \ - { "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_storage_information_t, available_capacity) }, \ - { "read_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_storage_information_t, read_speed) }, \ - { "write_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_storage_information_t, write_speed) }, \ - { "storage_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_storage_information_t, storage_id) }, \ - { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_storage_information_t, status) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION { \ - "STORAGE_INFORMATION", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_storage_information_t, time_boot_ms) }, \ - { "total_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_storage_information_t, total_capacity) }, \ - { "used_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_storage_information_t, used_capacity) }, \ - { "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_storage_information_t, available_capacity) }, \ - { "read_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_storage_information_t, read_speed) }, \ - { "write_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_storage_information_t, write_speed) }, \ - { "storage_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_storage_information_t, storage_id) }, \ - { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_storage_information_t, status) }, \ - } \ -} -#endif - -/** - * @brief Pack a storage_information 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_boot_ms Timestamp (milliseconds since system boot) - * @param storage_id Storage ID if there are multiple - * @param status Status of storage (0 not available, 1 unformatted, 2 formatted) - * @param total_capacity Total capacity in MiB - * @param used_capacity Used capacity in MiB - * @param available_capacity Available capacity in MiB - * @param read_speed Read speed in MiB/s - * @param write_speed Write speed in MiB/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_storage_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t storage_id, uint8_t status, float total_capacity, float used_capacity, float available_capacity, float read_speed, float write_speed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, total_capacity); - _mav_put_float(buf, 8, used_capacity); - _mav_put_float(buf, 12, available_capacity); - _mav_put_float(buf, 16, read_speed); - _mav_put_float(buf, 20, write_speed); - _mav_put_uint8_t(buf, 24, storage_id); - _mav_put_uint8_t(buf, 25, status); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN); -#else - mavlink_storage_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.total_capacity = total_capacity; - packet.used_capacity = used_capacity; - packet.available_capacity = available_capacity; - packet.read_speed = read_speed; - packet.write_speed = write_speed; - packet.storage_id = storage_id; - packet.status = status; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STORAGE_INFORMATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -} - -/** - * @brief Pack a storage_information message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param storage_id Storage ID if there are multiple - * @param status Status of storage (0 not available, 1 unformatted, 2 formatted) - * @param total_capacity Total capacity in MiB - * @param used_capacity Used capacity in MiB - * @param available_capacity Available capacity in MiB - * @param read_speed Read speed in MiB/s - * @param write_speed Write speed in MiB/s - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_storage_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t storage_id,uint8_t status,float total_capacity,float used_capacity,float available_capacity,float read_speed,float write_speed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, total_capacity); - _mav_put_float(buf, 8, used_capacity); - _mav_put_float(buf, 12, available_capacity); - _mav_put_float(buf, 16, read_speed); - _mav_put_float(buf, 20, write_speed); - _mav_put_uint8_t(buf, 24, storage_id); - _mav_put_uint8_t(buf, 25, status); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN); -#else - mavlink_storage_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.total_capacity = total_capacity; - packet.used_capacity = used_capacity; - packet.available_capacity = available_capacity; - packet.read_speed = read_speed; - packet.write_speed = write_speed; - packet.storage_id = storage_id; - packet.status = status; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STORAGE_INFORMATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -} - -/** - * @brief Encode a storage_information struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param storage_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_storage_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_storage_information_t* storage_information) -{ - return mavlink_msg_storage_information_pack(system_id, component_id, msg, storage_information->time_boot_ms, storage_information->storage_id, storage_information->status, storage_information->total_capacity, storage_information->used_capacity, storage_information->available_capacity, storage_information->read_speed, storage_information->write_speed); -} - -/** - * @brief Encode a storage_information struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param storage_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_storage_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_storage_information_t* storage_information) -{ - return mavlink_msg_storage_information_pack_chan(system_id, component_id, chan, msg, storage_information->time_boot_ms, storage_information->storage_id, storage_information->status, storage_information->total_capacity, storage_information->used_capacity, storage_information->available_capacity, storage_information->read_speed, storage_information->write_speed); -} - -/** - * @brief Send a storage_information message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param storage_id Storage ID if there are multiple - * @param status Status of storage (0 not available, 1 unformatted, 2 formatted) - * @param total_capacity Total capacity in MiB - * @param used_capacity Used capacity in MiB - * @param available_capacity Available capacity in MiB - * @param read_speed Read speed in MiB/s - * @param write_speed Write speed in MiB/s - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_storage_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t storage_id, uint8_t status, float total_capacity, float used_capacity, float available_capacity, float read_speed, float write_speed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, total_capacity); - _mav_put_float(buf, 8, used_capacity); - _mav_put_float(buf, 12, available_capacity); - _mav_put_float(buf, 16, read_speed); - _mav_put_float(buf, 20, write_speed); - _mav_put_uint8_t(buf, 24, storage_id); - _mav_put_uint8_t(buf, 25, status); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -#else - mavlink_storage_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.total_capacity = total_capacity; - packet.used_capacity = used_capacity; - packet.available_capacity = available_capacity; - packet.read_speed = read_speed; - packet.write_speed = write_speed; - packet.storage_id = storage_id; - packet.status = status; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -#endif -} - -/** - * @brief Send a storage_information message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_storage_information_send_struct(mavlink_channel_t chan, const mavlink_storage_information_t* storage_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_storage_information_send(chan, storage_information->time_boot_ms, storage_information->storage_id, storage_information->status, storage_information->total_capacity, storage_information->used_capacity, storage_information->available_capacity, storage_information->read_speed, storage_information->write_speed); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, (const char *)storage_information, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_storage_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t storage_id, uint8_t status, float total_capacity, float used_capacity, float available_capacity, float read_speed, float write_speed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, total_capacity); - _mav_put_float(buf, 8, used_capacity); - _mav_put_float(buf, 12, available_capacity); - _mav_put_float(buf, 16, read_speed); - _mav_put_float(buf, 20, write_speed); - _mav_put_uint8_t(buf, 24, storage_id); - _mav_put_uint8_t(buf, 25, status); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -#else - mavlink_storage_information_t *packet = (mavlink_storage_information_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->total_capacity = total_capacity; - packet->used_capacity = used_capacity; - packet->available_capacity = available_capacity; - packet->read_speed = read_speed; - packet->write_speed = write_speed; - packet->storage_id = storage_id; - packet->status = status; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE STORAGE_INFORMATION UNPACKING - - -/** - * @brief Get field time_boot_ms from storage_information message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_storage_information_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field storage_id from storage_information message - * - * @return Storage ID if there are multiple - */ -static inline uint8_t mavlink_msg_storage_information_get_storage_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field status from storage_information message - * - * @return Status of storage (0 not available, 1 unformatted, 2 formatted) - */ -static inline uint8_t mavlink_msg_storage_information_get_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field total_capacity from storage_information message - * - * @return Total capacity in MiB - */ -static inline float mavlink_msg_storage_information_get_total_capacity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field used_capacity from storage_information message - * - * @return Used capacity in MiB - */ -static inline float mavlink_msg_storage_information_get_used_capacity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field available_capacity from storage_information message - * - * @return Available capacity in MiB - */ -static inline float mavlink_msg_storage_information_get_available_capacity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field read_speed from storage_information message - * - * @return Read speed in MiB/s - */ -static inline float mavlink_msg_storage_information_get_read_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field write_speed from storage_information message - * - * @return Write speed in MiB/s - */ -static inline float mavlink_msg_storage_information_get_write_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a storage_information message into a struct - * - * @param msg The message to decode - * @param storage_information C-struct to decode the message contents into - */ -static inline void mavlink_msg_storage_information_decode(const mavlink_message_t* msg, mavlink_storage_information_t* storage_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - storage_information->time_boot_ms = mavlink_msg_storage_information_get_time_boot_ms(msg); - storage_information->total_capacity = mavlink_msg_storage_information_get_total_capacity(msg); - storage_information->used_capacity = mavlink_msg_storage_information_get_used_capacity(msg); - storage_information->available_capacity = mavlink_msg_storage_information_get_available_capacity(msg); - storage_information->read_speed = mavlink_msg_storage_information_get_read_speed(msg); - storage_information->write_speed = mavlink_msg_storage_information_get_write_speed(msg); - storage_information->storage_id = mavlink_msg_storage_information_get_storage_id(msg); - storage_information->status = mavlink_msg_storage_information_get_status(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN; - memset(storage_information, 0, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN); - memcpy(storage_information, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_sys_status.h b/include/mavlink/v2.0/common/mavlink_msg_sys_status.h deleted file mode 100644 index 28a85b5..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_sys_status.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE SYS_STATUS PACKING - -#define MAVLINK_MSG_ID_SYS_STATUS 1 - -MAVPACKED( -typedef struct __mavlink_sys_status_t { - uint32_t onboard_control_sensors_present; /*< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ - uint32_t onboard_control_sensors_enabled; /*< Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ - uint32_t onboard_control_sensors_health; /*< Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ - uint16_t load; /*< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000*/ - uint16_t voltage_battery; /*< Battery voltage, in millivolts (1 = 1 millivolt)*/ - int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/ - uint16_t drop_rate_comm; /*< Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ - uint16_t errors_comm; /*< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ - uint16_t errors_count1; /*< Autopilot-specific errors*/ - uint16_t errors_count2; /*< Autopilot-specific errors*/ - uint16_t errors_count3; /*< Autopilot-specific errors*/ - uint16_t errors_count4; /*< Autopilot-specific errors*/ - int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery*/ -}) mavlink_sys_status_t; - -#define MAVLINK_MSG_ID_SYS_STATUS_LEN 31 -#define MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN 31 -#define MAVLINK_MSG_ID_1_LEN 31 -#define MAVLINK_MSG_ID_1_MIN_LEN 31 - -#define MAVLINK_MSG_ID_SYS_STATUS_CRC 124 -#define MAVLINK_MSG_ID_1_CRC 124 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ - 1, \ - "SYS_STATUS", \ - 13, \ - { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \ - { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \ - { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \ - { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ - { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ - { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ - { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ - { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ - { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ - { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ - { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ - "SYS_STATUS", \ - 13, \ - { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \ - { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \ - { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \ - { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ - { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ - { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ - { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ - { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ - { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ - { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ - { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ - } \ -} -#endif - -/** - * @brief Pack a sys_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - - 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; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - - 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, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -} - -/** - * @brief Pack a sys_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - - 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; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - - 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, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -} - -/** - * @brief Encode a sys_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param sys_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) -{ - return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); -} - -/** - * @brief Encode a sys_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sys_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sys_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) -{ - return mavlink_msg_sys_status_pack_chan(system_id, component_id, chan, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); -} - -/** - * @brief Send a sys_status message - * @param chan MAVLink channel to send the message - * - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _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, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - mavlink_sys_status_t packet; - packet.onboard_control_sensors_present = onboard_control_sensors_present; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#endif -} - -/** - * @brief Send a sys_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_sys_status_send_struct(mavlink_channel_t chan, const mavlink_sys_status_t* sys_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_sys_status_send(chan, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)sys_status, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SYS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_sys_status_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _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, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - mavlink_sys_status_t *packet = (mavlink_sys_status_t *)msgbuf; - packet->onboard_control_sensors_present = onboard_control_sensors_present; - packet->onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet->onboard_control_sensors_health = onboard_control_sensors_health; - packet->load = load; - packet->voltage_battery = voltage_battery; - packet->current_battery = current_battery; - packet->drop_rate_comm = drop_rate_comm; - packet->errors_comm = errors_comm; - packet->errors_count1 = errors_count1; - packet->errors_count2 = errors_count2; - packet->errors_count3 = errors_count3; - packet->errors_count4 = errors_count4; - packet->battery_remaining = battery_remaining; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SYS_STATUS UNPACKING - - -/** - * @brief Get field onboard_control_sensors_present from sys_status message - * - * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field onboard_control_sensors_enabled from sys_status message - * - * @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field onboard_control_sensors_health from sys_status message - * - * @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field load from sys_status message - * - * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - */ -static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field voltage_battery from sys_status message - * - * @return Battery voltage, in millivolts (1 = 1 millivolt) - */ -static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field current_battery from sys_status message - * - * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - */ -static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field battery_remaining from sys_status message - * - * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - */ -static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 30); -} - -/** - * @brief Get field drop_rate_comm from sys_status message - * - * @return Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - */ -static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field errors_comm from sys_status message - * - * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field errors_count1 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field errors_count2 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field errors_count3 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field errors_count4 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Decode a sys_status message into a struct - * - * @param msg The message to decode - * @param sys_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg); - sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg); - sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg); - sys_status->load = mavlink_msg_sys_status_get_load(msg); - sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg); - sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg); - sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg); - sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg); - sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg); - sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg); - sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SYS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_SYS_STATUS_LEN; - memset(sys_status, 0, MAVLINK_MSG_ID_SYS_STATUS_LEN); - memcpy(sys_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_system_time.h b/include/mavlink/v2.0/common/mavlink_msg_system_time.h deleted file mode 100644 index 0e9b2ce..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_system_time.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE SYSTEM_TIME PACKING - -#define MAVLINK_MSG_ID_SYSTEM_TIME 2 - -MAVPACKED( -typedef struct __mavlink_system_time_t { - uint64_t time_unix_usec; /*< Timestamp of the master clock in microseconds since UNIX epoch.*/ - uint32_t time_boot_ms; /*< Timestamp of the component clock since boot time in milliseconds.*/ -}) mavlink_system_time_t; - -#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 -#define MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN 12 -#define MAVLINK_MSG_ID_2_LEN 12 -#define MAVLINK_MSG_ID_2_MIN_LEN 12 - -#define MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137 -#define MAVLINK_MSG_ID_2_CRC 137 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ - 2, \ - "SYSTEM_TIME", \ - 2, \ - { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ - "SYSTEM_TIME", \ - 2, \ - { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \ - } \ -} -#endif - -/** - * @brief Pack a system_time 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_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_unix_usec, uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -} - -/** - * @brief Pack a system_time message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_unix_usec,uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, 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, 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, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -} - -/** - * @brief Encode a system_time struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param system_time C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time) -{ - return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms); -} - -/** - * @brief Encode a system_time struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param system_time C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_system_time_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_system_time_t* system_time) -{ - return mavlink_msg_system_time_pack_chan(system_id, component_id, chan, msg, system_time->time_unix_usec, system_time->time_boot_ms); -} - -/** - * @brief Send a system_time message - * @param chan MAVLink channel to send the message - * - * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#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, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#endif -} - -/** - * @brief Send a system_time message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_system_time_send_struct(mavlink_channel_t chan, const mavlink_system_time_t* system_time) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_system_time_send(chan, system_time->time_unix_usec, system_time->time_boot_ms); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)system_time, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SYSTEM_TIME_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_system_time_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#else - mavlink_system_time_t *packet = (mavlink_system_time_t *)msgbuf; - 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, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SYSTEM_TIME UNPACKING - - -/** - * @brief Get field time_unix_usec from system_time message - * - * @return Timestamp of the master clock in microseconds since UNIX epoch. - */ -static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field time_boot_ms from system_time message - * - * @return Timestamp of the component clock since boot time in milliseconds. - */ -static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Decode a system_time message into a struct - * - * @param msg The message to decode - * @param system_time C-struct to decode the message contents into - */ -static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_SYSTEM_TIME_LEN? msg->len : MAVLINK_MSG_ID_SYSTEM_TIME_LEN; - memset(system_time, 0, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); - memcpy(system_time, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_terrain_check.h b/include/mavlink/v2.0/common/mavlink_msg_terrain_check.h deleted file mode 100644 index 820ff33..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_terrain_check.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_CHECK PACKING - -#define MAVLINK_MSG_ID_TERRAIN_CHECK 135 - -MAVPACKED( -typedef struct __mavlink_terrain_check_t { - int32_t lat; /*< Latitude (degrees *10^7)*/ - int32_t lon; /*< Longitude (degrees *10^7)*/ -}) mavlink_terrain_check_t; - -#define MAVLINK_MSG_ID_TERRAIN_CHECK_LEN 8 -#define MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN 8 -#define MAVLINK_MSG_ID_135_LEN 8 -#define MAVLINK_MSG_ID_135_MIN_LEN 8 - -#define MAVLINK_MSG_ID_TERRAIN_CHECK_CRC 203 -#define MAVLINK_MSG_ID_135_CRC 203 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_CHECK { \ - 135, \ - "TERRAIN_CHECK", \ - 2, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_check_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_check_t, lon) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_CHECK { \ - "TERRAIN_CHECK", \ - 2, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_check_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_check_t, lon) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_check 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 lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_check_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#else - mavlink_terrain_check_t packet; - packet.lat = lat; - packet.lon = lon; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -} - -/** - * @brief Pack a terrain_check message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_check_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#else - mavlink_terrain_check_t packet; - packet.lat = lat; - packet.lon = lon; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -} - -/** - * @brief Encode a terrain_check struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_check C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_check_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check) -{ - return mavlink_msg_terrain_check_pack(system_id, component_id, msg, terrain_check->lat, terrain_check->lon); -} - -/** - * @brief Encode a terrain_check struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_check C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_check_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check) -{ - return mavlink_msg_terrain_check_pack_chan(system_id, component_id, chan, msg, terrain_check->lat, terrain_check->lon); -} - -/** - * @brief Send a terrain_check message - * @param chan MAVLink channel to send the message - * - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_check_send(mavlink_channel_t chan, int32_t lat, int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#else - mavlink_terrain_check_t packet; - packet.lat = lat; - packet.lon = lon; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#endif -} - -/** - * @brief Send a terrain_check message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_check_send_struct(mavlink_channel_t chan, const mavlink_terrain_check_t* terrain_check) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_check_send(chan, terrain_check->lat, terrain_check->lon); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)terrain_check, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_CHECK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_check_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#else - mavlink_terrain_check_t *packet = (mavlink_terrain_check_t *)msgbuf; - packet->lat = lat; - packet->lon = lon; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_CHECK UNPACKING - - -/** - * @brief Get field lat from terrain_check message - * - * @return Latitude (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_check_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lon from terrain_check message - * - * @return Longitude (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_check_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Decode a terrain_check message into a struct - * - * @param msg The message to decode - * @param terrain_check C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_check_decode(const mavlink_message_t* msg, mavlink_terrain_check_t* terrain_check) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_check->lat = mavlink_msg_terrain_check_get_lat(msg); - terrain_check->lon = mavlink_msg_terrain_check_get_lon(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_CHECK_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_CHECK_LEN; - memset(terrain_check, 0, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); - memcpy(terrain_check, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_terrain_data.h b/include/mavlink/v2.0/common/mavlink_msg_terrain_data.h deleted file mode 100644 index ac9b9be..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_terrain_data.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_DATA PACKING - -#define MAVLINK_MSG_ID_TERRAIN_DATA 134 - -MAVPACKED( -typedef struct __mavlink_terrain_data_t { - int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/ - int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/ - uint16_t grid_spacing; /*< Grid spacing in meters*/ - int16_t data[16]; /*< Terrain data in meters AMSL*/ - uint8_t gridbit; /*< bit within the terrain request mask*/ -}) mavlink_terrain_data_t; - -#define MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43 -#define MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN 43 -#define MAVLINK_MSG_ID_134_LEN 43 -#define MAVLINK_MSG_ID_134_MIN_LEN 43 - -#define MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229 -#define MAVLINK_MSG_ID_134_CRC 229 - -#define MAVLINK_MSG_TERRAIN_DATA_FIELD_DATA_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \ - 134, \ - "TERRAIN_DATA", \ - 5, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \ - { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ - { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \ - "TERRAIN_DATA", \ - 5, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \ - { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ - { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_data 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 lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param gridbit bit within the terrain request mask - * @param data Terrain data in meters AMSL - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#else - mavlink_terrain_data_t packet; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - packet.gridbit = gridbit; - mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -} - -/** - * @brief Pack a terrain_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param gridbit bit within the terrain request mask - * @param data Terrain data in meters AMSL - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon,uint16_t grid_spacing,uint8_t gridbit,const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#else - mavlink_terrain_data_t packet; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - packet.gridbit = gridbit; - mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -} - -/** - * @brief Encode a terrain_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data) -{ - return mavlink_msg_terrain_data_pack(system_id, component_id, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); -} - -/** - * @brief Encode a terrain_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data) -{ - return mavlink_msg_terrain_data_pack_chan(system_id, component_id, chan, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); -} - -/** - * @brief Send a terrain_data message - * @param chan MAVLink channel to send the message - * - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param gridbit bit within the terrain request mask - * @param data Terrain data in meters AMSL - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_data_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#else - mavlink_terrain_data_t packet; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - packet.gridbit = gridbit; - mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#endif -} - -/** - * @brief Send a terrain_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_data_send_struct(mavlink_channel_t chan, const mavlink_terrain_data_t* terrain_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_data_send(chan, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)terrain_data, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#else - mavlink_terrain_data_t *packet = (mavlink_terrain_data_t *)msgbuf; - packet->lat = lat; - packet->lon = lon; - packet->grid_spacing = grid_spacing; - packet->gridbit = gridbit; - mav_array_memcpy(packet->data, data, sizeof(int16_t)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_DATA UNPACKING - - -/** - * @brief Get field lat from terrain_data message - * - * @return Latitude of SW corner of first grid (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_data_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lon from terrain_data message - * - * @return Longitude of SW corner of first grid (in degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_data_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field grid_spacing from terrain_data message - * - * @return Grid spacing in meters - */ -static inline uint16_t mavlink_msg_terrain_data_get_grid_spacing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field gridbit from terrain_data message - * - * @return bit within the terrain request mask - */ -static inline uint8_t mavlink_msg_terrain_data_get_gridbit(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field data from terrain_data message - * - * @return Terrain data in meters AMSL - */ -static inline uint16_t mavlink_msg_terrain_data_get_data(const mavlink_message_t* msg, int16_t *data) -{ - return _MAV_RETURN_int16_t_array(msg, data, 16, 10); -} - -/** - * @brief Decode a terrain_data message into a struct - * - * @param msg The message to decode - * @param terrain_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_data_decode(const mavlink_message_t* msg, mavlink_terrain_data_t* terrain_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_data->lat = mavlink_msg_terrain_data_get_lat(msg); - terrain_data->lon = mavlink_msg_terrain_data_get_lon(msg); - terrain_data->grid_spacing = mavlink_msg_terrain_data_get_grid_spacing(msg); - mavlink_msg_terrain_data_get_data(msg, terrain_data->data); - terrain_data->gridbit = mavlink_msg_terrain_data_get_gridbit(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_DATA_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_DATA_LEN; - memset(terrain_data, 0, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); - memcpy(terrain_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_terrain_report.h b/include/mavlink/v2.0/common/mavlink_msg_terrain_report.h deleted file mode 100644 index 1374db5..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_terrain_report.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_REPORT PACKING - -#define MAVLINK_MSG_ID_TERRAIN_REPORT 136 - -MAVPACKED( -typedef struct __mavlink_terrain_report_t { - int32_t lat; /*< Latitude (degrees *10^7)*/ - int32_t lon; /*< Longitude (degrees *10^7)*/ - float terrain_height; /*< Terrain height in meters AMSL*/ - float current_height; /*< Current vehicle height above lat/lon terrain height (meters)*/ - uint16_t spacing; /*< grid spacing (zero if terrain at this location unavailable)*/ - uint16_t pending; /*< Number of 4x4 terrain blocks waiting to be received or read from disk*/ - uint16_t loaded; /*< Number of 4x4 terrain blocks in memory*/ -}) mavlink_terrain_report_t; - -#define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22 -#define MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN 22 -#define MAVLINK_MSG_ID_136_LEN 22 -#define MAVLINK_MSG_ID_136_MIN_LEN 22 - -#define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC 1 -#define MAVLINK_MSG_ID_136_CRC 1 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT { \ - 136, \ - "TERRAIN_REPORT", \ - 7, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \ - { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \ - { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \ - { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ - { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \ - { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT { \ - "TERRAIN_REPORT", \ - 7, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \ - { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \ - { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \ - { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ - { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \ - { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_report 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 lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height Terrain height in meters AMSL - * @param current_height Current vehicle height above lat/lon terrain height (meters) - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#else - mavlink_terrain_report_t packet; - packet.lat = lat; - packet.lon = lon; - packet.terrain_height = terrain_height; - packet.current_height = current_height; - packet.spacing = spacing; - packet.pending = pending; - packet.loaded = loaded; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -} - -/** - * @brief Pack a terrain_report message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height Terrain height in meters AMSL - * @param current_height Current vehicle height above lat/lon terrain height (meters) - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon,uint16_t spacing,float terrain_height,float current_height,uint16_t pending,uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#else - mavlink_terrain_report_t packet; - packet.lat = lat; - packet.lon = lon; - packet.terrain_height = terrain_height; - packet.current_height = current_height; - packet.spacing = spacing; - packet.pending = pending; - packet.loaded = loaded; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -} - -/** - * @brief Encode a terrain_report struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_report C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report) -{ - return mavlink_msg_terrain_report_pack(system_id, component_id, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); -} - -/** - * @brief Encode a terrain_report struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_report C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report) -{ - return mavlink_msg_terrain_report_pack_chan(system_id, component_id, chan, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); -} - -/** - * @brief Send a terrain_report message - * @param chan MAVLink channel to send the message - * - * @param lat Latitude (degrees *10^7) - * @param lon Longitude (degrees *10^7) - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height Terrain height in meters AMSL - * @param current_height Current vehicle height above lat/lon terrain height (meters) - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_report_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#else - mavlink_terrain_report_t packet; - packet.lat = lat; - packet.lon = lon; - packet.terrain_height = terrain_height; - packet.current_height = current_height; - packet.spacing = spacing; - packet.pending = pending; - packet.loaded = loaded; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#endif -} - -/** - * @brief Send a terrain_report message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_report_send_struct(mavlink_channel_t chan, const mavlink_terrain_report_t* terrain_report) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_report_send(chan, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)terrain_report, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#else - mavlink_terrain_report_t *packet = (mavlink_terrain_report_t *)msgbuf; - packet->lat = lat; - packet->lon = lon; - packet->terrain_height = terrain_height; - packet->current_height = current_height; - packet->spacing = spacing; - packet->pending = pending; - packet->loaded = loaded; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_REPORT UNPACKING - - -/** - * @brief Get field lat from terrain_report message - * - * @return Latitude (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_report_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lon from terrain_report message - * - * @return Longitude (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_report_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field spacing from terrain_report message - * - * @return grid spacing (zero if terrain at this location unavailable) - */ -static inline uint16_t mavlink_msg_terrain_report_get_spacing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field terrain_height from terrain_report message - * - * @return Terrain height in meters AMSL - */ -static inline float mavlink_msg_terrain_report_get_terrain_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field current_height from terrain_report message - * - * @return Current vehicle height above lat/lon terrain height (meters) - */ -static inline float mavlink_msg_terrain_report_get_current_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field pending from terrain_report message - * - * @return Number of 4x4 terrain blocks waiting to be received or read from disk - */ -static inline uint16_t mavlink_msg_terrain_report_get_pending(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field loaded from terrain_report message - * - * @return Number of 4x4 terrain blocks in memory - */ -static inline uint16_t mavlink_msg_terrain_report_get_loaded(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Decode a terrain_report message into a struct - * - * @param msg The message to decode - * @param terrain_report C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_report_decode(const mavlink_message_t* msg, mavlink_terrain_report_t* terrain_report) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_report->lat = mavlink_msg_terrain_report_get_lat(msg); - terrain_report->lon = mavlink_msg_terrain_report_get_lon(msg); - terrain_report->terrain_height = mavlink_msg_terrain_report_get_terrain_height(msg); - terrain_report->current_height = mavlink_msg_terrain_report_get_current_height(msg); - terrain_report->spacing = mavlink_msg_terrain_report_get_spacing(msg); - terrain_report->pending = mavlink_msg_terrain_report_get_pending(msg); - terrain_report->loaded = mavlink_msg_terrain_report_get_loaded(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_REPORT_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_REPORT_LEN; - memset(terrain_report, 0, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); - memcpy(terrain_report, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_terrain_request.h b/include/mavlink/v2.0/common/mavlink_msg_terrain_request.h deleted file mode 100644 index 8924ed4..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_terrain_request.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_REQUEST PACKING - -#define MAVLINK_MSG_ID_TERRAIN_REQUEST 133 - -MAVPACKED( -typedef struct __mavlink_terrain_request_t { - uint64_t mask; /*< Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)*/ - int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/ - int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/ - uint16_t grid_spacing; /*< Grid spacing in meters*/ -}) mavlink_terrain_request_t; - -#define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18 -#define MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN 18 -#define MAVLINK_MSG_ID_133_LEN 18 -#define MAVLINK_MSG_ID_133_MIN_LEN 18 - -#define MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC 6 -#define MAVLINK_MSG_ID_133_CRC 6 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \ - 133, \ - "TERRAIN_REQUEST", \ - 4, \ - { { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \ - "TERRAIN_REQUEST", \ - 4, \ - { { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_request 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 lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#else - mavlink_terrain_request_t packet; - packet.mask = mask; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -} - -/** - * @brief Pack a terrain_request message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon,uint16_t grid_spacing,uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#else - mavlink_terrain_request_t packet; - packet.mask = mask; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -} - -/** - * @brief Encode a terrain_request struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request) -{ - return mavlink_msg_terrain_request_pack(system_id, component_id, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); -} - -/** - * @brief Encode a terrain_request struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request) -{ - return mavlink_msg_terrain_request_pack_chan(system_id, component_id, chan, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); -} - -/** - * @brief Send a terrain_request message - * @param chan MAVLink channel to send the message - * - * @param lat Latitude of SW corner of first grid (degrees *10^7) - * @param lon Longitude of SW corner of first grid (in degrees *10^7) - * @param grid_spacing Grid spacing in meters - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_request_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#else - mavlink_terrain_request_t packet; - packet.mask = mask; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#endif -} - -/** - * @brief Send a terrain_request message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_request_send_struct(mavlink_channel_t chan, const mavlink_terrain_request_t* terrain_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_request_send(chan, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)terrain_request, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#else - mavlink_terrain_request_t *packet = (mavlink_terrain_request_t *)msgbuf; - packet->mask = mask; - packet->lat = lat; - packet->lon = lon; - packet->grid_spacing = grid_spacing; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_REQUEST UNPACKING - - -/** - * @brief Get field lat from terrain_request message - * - * @return Latitude of SW corner of first grid (degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_request_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from terrain_request message - * - * @return Longitude of SW corner of first grid (in degrees *10^7) - */ -static inline int32_t mavlink_msg_terrain_request_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field grid_spacing from terrain_request message - * - * @return Grid spacing in meters - */ -static inline uint16_t mavlink_msg_terrain_request_get_grid_spacing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field mask from terrain_request message - * - * @return Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - */ -static inline uint64_t mavlink_msg_terrain_request_get_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Decode a terrain_request message into a struct - * - * @param msg The message to decode - * @param terrain_request C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_request_decode(const mavlink_message_t* msg, mavlink_terrain_request_t* terrain_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_request->mask = mavlink_msg_terrain_request_get_mask(msg); - terrain_request->lat = mavlink_msg_terrain_request_get_lat(msg); - terrain_request->lon = mavlink_msg_terrain_request_get_lon(msg); - terrain_request->grid_spacing = mavlink_msg_terrain_request_get_grid_spacing(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN; - memset(terrain_request, 0, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); - memcpy(terrain_request, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_timesync.h b/include/mavlink/v2.0/common/mavlink_msg_timesync.h deleted file mode 100644 index 395211f..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_timesync.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE TIMESYNC PACKING - -#define MAVLINK_MSG_ID_TIMESYNC 111 - -MAVPACKED( -typedef struct __mavlink_timesync_t { - int64_t tc1; /*< Time sync timestamp 1*/ - int64_t ts1; /*< Time sync timestamp 2*/ -}) mavlink_timesync_t; - -#define MAVLINK_MSG_ID_TIMESYNC_LEN 16 -#define MAVLINK_MSG_ID_TIMESYNC_MIN_LEN 16 -#define MAVLINK_MSG_ID_111_LEN 16 -#define MAVLINK_MSG_ID_111_MIN_LEN 16 - -#define MAVLINK_MSG_ID_TIMESYNC_CRC 34 -#define MAVLINK_MSG_ID_111_CRC 34 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TIMESYNC { \ - 111, \ - "TIMESYNC", \ - 2, \ - { { "tc1", NULL, MAVLINK_TYPE_INT64_T, 0, 0, offsetof(mavlink_timesync_t, tc1) }, \ - { "ts1", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_timesync_t, ts1) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TIMESYNC { \ - "TIMESYNC", \ - 2, \ - { { "tc1", NULL, MAVLINK_TYPE_INT64_T, 0, 0, offsetof(mavlink_timesync_t, tc1) }, \ - { "ts1", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_timesync_t, ts1) }, \ - } \ -} -#endif - -/** - * @brief Pack a timesync 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 tc1 Time sync timestamp 1 - * @param ts1 Time sync timestamp 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_timesync_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int64_t tc1, int64_t ts1) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN); -#else - mavlink_timesync_t packet; - packet.tc1 = tc1; - packet.ts1 = ts1; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TIMESYNC; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -} - -/** - * @brief Pack a timesync message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param tc1 Time sync timestamp 1 - * @param ts1 Time sync timestamp 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_timesync_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int64_t tc1,int64_t ts1) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN); -#else - mavlink_timesync_t packet; - packet.tc1 = tc1; - packet.ts1 = ts1; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TIMESYNC; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -} - -/** - * @brief Encode a timesync struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param timesync C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_timesync_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_timesync_t* timesync) -{ - return mavlink_msg_timesync_pack(system_id, component_id, msg, timesync->tc1, timesync->ts1); -} - -/** - * @brief Encode a timesync struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param timesync C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_timesync_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_timesync_t* timesync) -{ - return mavlink_msg_timesync_pack_chan(system_id, component_id, chan, msg, timesync->tc1, timesync->ts1); -} - -/** - * @brief Send a timesync message - * @param chan MAVLink channel to send the message - * - * @param tc1 Time sync timestamp 1 - * @param ts1 Time sync timestamp 2 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_timesync_send(mavlink_channel_t chan, int64_t tc1, int64_t ts1) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#else - mavlink_timesync_t packet; - packet.tc1 = tc1; - packet.ts1 = ts1; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)&packet, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#endif -} - -/** - * @brief Send a timesync message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_timesync_send_struct(mavlink_channel_t chan, const mavlink_timesync_t* timesync) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_timesync_send(chan, timesync->tc1, timesync->ts1); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)timesync, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TIMESYNC_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_timesync_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int64_t tc1, int64_t ts1) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#else - mavlink_timesync_t *packet = (mavlink_timesync_t *)msgbuf; - packet->tc1 = tc1; - packet->ts1 = ts1; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)packet, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TIMESYNC UNPACKING - - -/** - * @brief Get field tc1 from timesync message - * - * @return Time sync timestamp 1 - */ -static inline int64_t mavlink_msg_timesync_get_tc1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int64_t(msg, 0); -} - -/** - * @brief Get field ts1 from timesync message - * - * @return Time sync timestamp 2 - */ -static inline int64_t mavlink_msg_timesync_get_ts1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int64_t(msg, 8); -} - -/** - * @brief Decode a timesync message into a struct - * - * @param msg The message to decode - * @param timesync C-struct to decode the message contents into - */ -static inline void mavlink_msg_timesync_decode(const mavlink_message_t* msg, mavlink_timesync_t* timesync) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - timesync->tc1 = mavlink_msg_timesync_get_tc1(msg); - timesync->ts1 = mavlink_msg_timesync_get_ts1(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TIMESYNC_LEN? msg->len : MAVLINK_MSG_ID_TIMESYNC_LEN; - memset(timesync, 0, MAVLINK_MSG_ID_TIMESYNC_LEN); - memcpy(timesync, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_v2_extension.h b/include/mavlink/v2.0/common/mavlink_msg_v2_extension.h deleted file mode 100644 index 31777f2..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_v2_extension.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE V2_EXTENSION PACKING - -#define MAVLINK_MSG_ID_V2_EXTENSION 248 - -MAVPACKED( -typedef struct __mavlink_v2_extension_t { - uint16_t message_type; /*< A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.*/ - uint8_t target_network; /*< Network ID (0 for broadcast)*/ - uint8_t target_system; /*< System ID (0 for broadcast)*/ - uint8_t target_component; /*< Component ID (0 for broadcast)*/ - uint8_t payload[249]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/ -}) mavlink_v2_extension_t; - -#define MAVLINK_MSG_ID_V2_EXTENSION_LEN 254 -#define MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN 254 -#define MAVLINK_MSG_ID_248_LEN 254 -#define MAVLINK_MSG_ID_248_MIN_LEN 254 - -#define MAVLINK_MSG_ID_V2_EXTENSION_CRC 8 -#define MAVLINK_MSG_ID_248_CRC 8 - -#define MAVLINK_MSG_V2_EXTENSION_FIELD_PAYLOAD_LEN 249 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \ - 248, \ - "V2_EXTENSION", \ - 5, \ - { { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ - { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \ - "V2_EXTENSION", \ - 5, \ - { { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ - { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \ - } \ -} -#endif - -/** - * @brief Pack a v2_extension message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_v2_extension_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#else - mavlink_v2_extension_t packet; - packet.message_type = message_type; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -} - -/** - * @brief Pack a v2_extension message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_v2_extension_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_network,uint8_t target_system,uint8_t target_component,uint16_t message_type,const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#else - mavlink_v2_extension_t packet; - packet.message_type = message_type; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -} - -/** - * @brief Encode a v2_extension struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param v2_extension C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_v2_extension_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension) -{ - return mavlink_msg_v2_extension_pack(system_id, component_id, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); -} - -/** - * @brief Encode a v2_extension struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param v2_extension C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_v2_extension_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension) -{ - return mavlink_msg_v2_extension_pack_chan(system_id, component_id, chan, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); -} - -/** - * @brief Send a v2_extension message - * @param chan MAVLink channel to send the message - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_v2_extension_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#else - mavlink_v2_extension_t packet; - packet.message_type = message_type; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#endif -} - -/** - * @brief Send a v2_extension message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_v2_extension_send_struct(mavlink_channel_t chan, const mavlink_v2_extension_t* v2_extension) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_v2_extension_send(chan, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)v2_extension, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_V2_EXTENSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_v2_extension_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#else - mavlink_v2_extension_t *packet = (mavlink_v2_extension_t *)msgbuf; - packet->message_type = message_type; - packet->target_network = target_network; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE V2_EXTENSION UNPACKING - - -/** - * @brief Get field target_network from v2_extension message - * - * @return Network ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_v2_extension_get_target_network(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_system from v2_extension message - * - * @return System ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_v2_extension_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field target_component from v2_extension message - * - * @return Component ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_v2_extension_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field message_type from v2_extension message - * - * @return A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - */ -static inline uint16_t mavlink_msg_v2_extension_get_message_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field payload from v2_extension message - * - * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - */ -static inline uint16_t mavlink_msg_v2_extension_get_payload(const mavlink_message_t* msg, uint8_t *payload) -{ - return _MAV_RETURN_uint8_t_array(msg, payload, 249, 5); -} - -/** - * @brief Decode a v2_extension message into a struct - * - * @param msg The message to decode - * @param v2_extension C-struct to decode the message contents into - */ -static inline void mavlink_msg_v2_extension_decode(const mavlink_message_t* msg, mavlink_v2_extension_t* v2_extension) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - v2_extension->message_type = mavlink_msg_v2_extension_get_message_type(msg); - v2_extension->target_network = mavlink_msg_v2_extension_get_target_network(msg); - v2_extension->target_system = mavlink_msg_v2_extension_get_target_system(msg); - v2_extension->target_component = mavlink_msg_v2_extension_get_target_component(msg); - mavlink_msg_v2_extension_get_payload(msg, v2_extension->payload); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_V2_EXTENSION_LEN? msg->len : MAVLINK_MSG_ID_V2_EXTENSION_LEN; - memset(v2_extension, 0, MAVLINK_MSG_ID_V2_EXTENSION_LEN); - memcpy(v2_extension, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_vfr_hud.h b/include/mavlink/v2.0/common/mavlink_msg_vfr_hud.h deleted file mode 100644 index 1700dd0..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_vfr_hud.h +++ /dev/null @@ -1,338 +0,0 @@ -#pragma once -// MESSAGE VFR_HUD PACKING - -#define MAVLINK_MSG_ID_VFR_HUD 74 - -MAVPACKED( -typedef struct __mavlink_vfr_hud_t { - float airspeed; /*< Current airspeed in m/s*/ - float groundspeed; /*< Current ground speed in m/s*/ - float alt; /*< Current altitude (MSL), in meters*/ - float climb; /*< Current climb rate in meters/second*/ - int16_t heading; /*< Current heading in degrees, in compass units (0..360, 0=north)*/ - uint16_t throttle; /*< Current throttle setting in integer percent, 0 to 100*/ -}) mavlink_vfr_hud_t; - -#define MAVLINK_MSG_ID_VFR_HUD_LEN 20 -#define MAVLINK_MSG_ID_VFR_HUD_MIN_LEN 20 -#define MAVLINK_MSG_ID_74_LEN 20 -#define MAVLINK_MSG_ID_74_MIN_LEN 20 - -#define MAVLINK_MSG_ID_VFR_HUD_CRC 20 -#define MAVLINK_MSG_ID_74_CRC 20 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VFR_HUD { \ - 74, \ - "VFR_HUD", \ - 6, \ - { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ - { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ - { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ - { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VFR_HUD { \ - "VFR_HUD", \ - 6, \ - { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ - { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ - { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ - { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ - } \ -} -#endif - -/** - * @brief Pack a vfr_hud 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 airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - - 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, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -} - -/** - * @brief Pack a vfr_hud message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - - 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, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -} - -/** - * @brief Encode a vfr_hud struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vfr_hud C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) -{ - return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); -} - -/** - * @brief Encode a vfr_hud struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vfr_hud C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vfr_hud_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) -{ - return mavlink_msg_vfr_hud_pack_chan(system_id, component_id, chan, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); -} - -/** - * @brief Send a vfr_hud message - * @param chan MAVLink channel to send the message - * - * @param airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[MAVLINK_MSG_ID_VFR_HUD_LEN]; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _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, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#endif -} - -/** - * @brief Send a vfr_hud message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vfr_hud_send_struct(mavlink_channel_t chan, const mavlink_vfr_hud_t* vfr_hud) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vfr_hud_send(chan, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)vfr_hud, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VFR_HUD_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vfr_hud_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _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, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - mavlink_vfr_hud_t *packet = (mavlink_vfr_hud_t *)msgbuf; - packet->airspeed = airspeed; - packet->groundspeed = groundspeed; - packet->alt = alt; - packet->climb = climb; - packet->heading = heading; - packet->throttle = throttle; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VFR_HUD UNPACKING - - -/** - * @brief Get field airspeed from vfr_hud message - * - * @return Current airspeed in m/s - */ -static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field groundspeed from vfr_hud message - * - * @return Current ground speed in m/s - */ -static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field heading from vfr_hud message - * - * @return Current heading in degrees, in compass units (0..360, 0=north) - */ -static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field throttle from vfr_hud message - * - * @return Current throttle setting in integer percent, 0 to 100 - */ -static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field alt from vfr_hud message - * - * @return Current altitude (MSL), in meters - */ -static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field climb from vfr_hud message - * - * @return Current climb rate in meters/second - */ -static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a vfr_hud message into a struct - * - * @param msg The message to decode - * @param vfr_hud C-struct to decode the message contents into - */ -static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg); - vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg); - vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg); - vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg); - vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg); - vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VFR_HUD_LEN? msg->len : MAVLINK_MSG_ID_VFR_HUD_LEN; - memset(vfr_hud, 0, MAVLINK_MSG_ID_VFR_HUD_LEN); - memcpy(vfr_hud, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_vibration.h b/include/mavlink/v2.0/common/mavlink_msg_vibration.h deleted file mode 100644 index a8760f7..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_vibration.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE VIBRATION PACKING - -#define MAVLINK_MSG_ID_VIBRATION 241 - -MAVPACKED( -typedef struct __mavlink_vibration_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float vibration_x; /*< Vibration levels on X-axis*/ - float vibration_y; /*< Vibration levels on Y-axis*/ - float vibration_z; /*< Vibration levels on Z-axis*/ - uint32_t clipping_0; /*< first accelerometer clipping count*/ - uint32_t clipping_1; /*< second accelerometer clipping count*/ - uint32_t clipping_2; /*< third accelerometer clipping count*/ -}) mavlink_vibration_t; - -#define MAVLINK_MSG_ID_VIBRATION_LEN 32 -#define MAVLINK_MSG_ID_VIBRATION_MIN_LEN 32 -#define MAVLINK_MSG_ID_241_LEN 32 -#define MAVLINK_MSG_ID_241_MIN_LEN 32 - -#define MAVLINK_MSG_ID_VIBRATION_CRC 90 -#define MAVLINK_MSG_ID_241_CRC 90 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VIBRATION { \ - 241, \ - "VIBRATION", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \ - { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \ - { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \ - { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \ - { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \ - { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \ - { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VIBRATION { \ - "VIBRATION", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \ - { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \ - { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \ - { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \ - { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \ - { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \ - { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \ - } \ -} -#endif - -/** - * @brief Pack a vibration 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 (micros since boot or Unix epoch) - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN); -#else - mavlink_vibration_t packet; - packet.time_usec = time_usec; - packet.vibration_x = vibration_x; - packet.vibration_y = vibration_y; - packet.vibration_z = vibration_z; - packet.clipping_0 = clipping_0; - packet.clipping_1 = clipping_1; - packet.clipping_2 = clipping_2; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIBRATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -} - -/** - * @brief Pack a vibration message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float vibration_x,float vibration_y,float vibration_z,uint32_t clipping_0,uint32_t clipping_1,uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN); -#else - mavlink_vibration_t packet; - packet.time_usec = time_usec; - packet.vibration_x = vibration_x; - packet.vibration_y = vibration_y; - packet.vibration_z = vibration_z; - packet.clipping_0 = clipping_0; - packet.clipping_1 = clipping_1; - packet.clipping_2 = clipping_2; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIBRATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -} - -/** - * @brief Encode a vibration struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vibration C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vibration_t* vibration) -{ - return mavlink_msg_vibration_pack(system_id, component_id, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); -} - -/** - * @brief Encode a vibration struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vibration C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vibration_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vibration_t* vibration) -{ - return mavlink_msg_vibration_pack_chan(system_id, component_id, chan, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); -} - -/** - * @brief Send a vibration message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vibration_send(mavlink_channel_t chan, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#else - mavlink_vibration_t packet; - packet.time_usec = time_usec; - packet.vibration_x = vibration_x; - packet.vibration_y = vibration_y; - packet.vibration_z = vibration_z; - packet.clipping_0 = clipping_0; - packet.clipping_1 = clipping_1; - packet.clipping_2 = clipping_2; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)&packet, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#endif -} - -/** - * @brief Send a vibration message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vibration_send_struct(mavlink_channel_t chan, const mavlink_vibration_t* vibration) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vibration_send(chan, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)vibration, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VIBRATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vibration_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#else - mavlink_vibration_t *packet = (mavlink_vibration_t *)msgbuf; - packet->time_usec = time_usec; - packet->vibration_x = vibration_x; - packet->vibration_y = vibration_y; - packet->vibration_z = vibration_z; - packet->clipping_0 = clipping_0; - packet->clipping_1 = clipping_1; - packet->clipping_2 = clipping_2; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)packet, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VIBRATION UNPACKING - - -/** - * @brief Get field time_usec from vibration message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_vibration_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field vibration_x from vibration message - * - * @return Vibration levels on X-axis - */ -static inline float mavlink_msg_vibration_get_vibration_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field vibration_y from vibration message - * - * @return Vibration levels on Y-axis - */ -static inline float mavlink_msg_vibration_get_vibration_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vibration_z from vibration message - * - * @return Vibration levels on Z-axis - */ -static inline float mavlink_msg_vibration_get_vibration_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field clipping_0 from vibration message - * - * @return first accelerometer clipping count - */ -static inline uint32_t mavlink_msg_vibration_get_clipping_0(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field clipping_1 from vibration message - * - * @return second accelerometer clipping count - */ -static inline uint32_t mavlink_msg_vibration_get_clipping_1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 24); -} - -/** - * @brief Get field clipping_2 from vibration message - * - * @return third accelerometer clipping count - */ -static inline uint32_t mavlink_msg_vibration_get_clipping_2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 28); -} - -/** - * @brief Decode a vibration message into a struct - * - * @param msg The message to decode - * @param vibration C-struct to decode the message contents into - */ -static inline void mavlink_msg_vibration_decode(const mavlink_message_t* msg, mavlink_vibration_t* vibration) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vibration->time_usec = mavlink_msg_vibration_get_time_usec(msg); - vibration->vibration_x = mavlink_msg_vibration_get_vibration_x(msg); - vibration->vibration_y = mavlink_msg_vibration_get_vibration_y(msg); - vibration->vibration_z = mavlink_msg_vibration_get_vibration_z(msg); - vibration->clipping_0 = mavlink_msg_vibration_get_clipping_0(msg); - vibration->clipping_1 = mavlink_msg_vibration_get_clipping_1(msg); - vibration->clipping_2 = mavlink_msg_vibration_get_clipping_2(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VIBRATION_LEN? msg->len : MAVLINK_MSG_ID_VIBRATION_LEN; - memset(vibration, 0, MAVLINK_MSG_ID_VIBRATION_LEN); - memcpy(vibration, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_vicon_position_estimate.h b/include/mavlink/v2.0/common/mavlink_msg_vicon_position_estimate.h deleted file mode 100644 index 5813b74..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_vicon_position_estimate.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE VICON_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104 - -MAVPACKED( -typedef struct __mavlink_vicon_position_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X position*/ - float y; /*< Global Y position*/ - float z; /*< Global Z position*/ - float roll; /*< Roll angle in rad*/ - float pitch; /*< Pitch angle in rad*/ - float yaw; /*< Yaw angle in rad*/ -}) mavlink_vicon_position_estimate_t; - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN 32 -#define MAVLINK_MSG_ID_104_LEN 32 -#define MAVLINK_MSG_ID_104_MIN_LEN 32 - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC 56 -#define MAVLINK_MSG_ID_104_CRC 56 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ - 104, \ - "VICON_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ - "VICON_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a vicon_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Pack a vicon_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Encode a vicon_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vicon_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ - return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); -} - -/** - * @brief Encode a vicon_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vicon_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ - return mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, chan, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); -} - -/** - * @brief Send a vicon_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a vicon_position_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vicon_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vicon_position_estimate_send(chan, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)vicon_position_estimate, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vicon_position_estimate_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - mavlink_vicon_position_estimate_t *packet = (mavlink_vicon_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VICON_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vicon_position_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vicon_position_estimate message - * - * @return Global X position - */ -static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vicon_position_estimate message - * - * @return Global Y position - */ -static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vicon_position_estimate message - * - * @return Global Z position - */ -static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from vicon_position_estimate message - * - * @return Roll angle in rad - */ -static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from vicon_position_estimate message - * - * @return Pitch angle in rad - */ -static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from vicon_position_estimate message - * - * @return Yaw angle in rad - */ -static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a vicon_position_estimate message into a struct - * - * @param msg The message to decode - * @param vicon_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg); - vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg); - vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg); - vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg); - vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN; - memset(vicon_position_estimate, 0, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); - memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_video_stream_information.h b/include/mavlink/v2.0/common/mavlink_msg_video_stream_information.h deleted file mode 100644 index 19a0346..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_video_stream_information.h +++ /dev/null @@ -1,380 +0,0 @@ -#pragma once -// MESSAGE VIDEO_STREAM_INFORMATION PACKING - -#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION 269 - -MAVPACKED( -typedef struct __mavlink_video_stream_information_t { - float framerate; /*< Frames per second*/ - uint32_t bitrate; /*< Bit rate in bits per second*/ - uint16_t resolution_h; /*< Resolution horizontal in pixels*/ - uint16_t resolution_v; /*< Resolution vertical in pixels*/ - uint16_t rotation; /*< Video image rotation clockwise*/ - uint8_t camera_id; /*< Camera ID (1 for first, 2 for second, etc.)*/ - uint8_t status; /*< Current status of video streaming (0: not running, 1: in progress)*/ - char uri[230]; /*< Video stream URI*/ -}) mavlink_video_stream_information_t; - -#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN 246 -#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN 246 -#define MAVLINK_MSG_ID_269_LEN 246 -#define MAVLINK_MSG_ID_269_MIN_LEN 246 - -#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC 58 -#define MAVLINK_MSG_ID_269_CRC 58 - -#define MAVLINK_MSG_VIDEO_STREAM_INFORMATION_FIELD_URI_LEN 230 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION { \ - 269, \ - "VIDEO_STREAM_INFORMATION", \ - 8, \ - { { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_information_t, framerate) }, \ - { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_video_stream_information_t, bitrate) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_information_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_video_stream_information_t, resolution_v) }, \ - { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_video_stream_information_t, rotation) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_video_stream_information_t, camera_id) }, \ - { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_video_stream_information_t, status) }, \ - { "uri", NULL, MAVLINK_TYPE_CHAR, 230, 16, offsetof(mavlink_video_stream_information_t, uri) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION { \ - "VIDEO_STREAM_INFORMATION", \ - 8, \ - { { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_information_t, framerate) }, \ - { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_video_stream_information_t, bitrate) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_information_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_video_stream_information_t, resolution_v) }, \ - { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_video_stream_information_t, rotation) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_video_stream_information_t, camera_id) }, \ - { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_video_stream_information_t, status) }, \ - { "uri", NULL, MAVLINK_TYPE_CHAR, 230, 16, offsetof(mavlink_video_stream_information_t, uri) }, \ - } \ -} -#endif - -/** - * @brief Pack a video_stream_information 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 camera_id Camera ID (1 for first, 2 for second, etc.) - * @param status Current status of video streaming (0: not running, 1: in progress) - * @param framerate Frames per second - * @param resolution_h Resolution horizontal in pixels - * @param resolution_v Resolution vertical in pixels - * @param bitrate Bit rate in bits per second - * @param rotation Video image rotation clockwise - * @param uri Video stream URI - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_video_stream_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t camera_id, uint8_t status, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, resolution_h); - _mav_put_uint16_t(buf, 10, resolution_v); - _mav_put_uint16_t(buf, 12, rotation); - _mav_put_uint8_t(buf, 14, camera_id); - _mav_put_uint8_t(buf, 15, status); - _mav_put_char_array(buf, 16, uri, 230); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN); -#else - mavlink_video_stream_information_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.camera_id = camera_id; - packet.status = status; - mav_array_memcpy(packet.uri, uri, sizeof(char)*230); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -} - -/** - * @brief Pack a video_stream_information message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_id Camera ID (1 for first, 2 for second, etc.) - * @param status Current status of video streaming (0: not running, 1: in progress) - * @param framerate Frames per second - * @param resolution_h Resolution horizontal in pixels - * @param resolution_v Resolution vertical in pixels - * @param bitrate Bit rate in bits per second - * @param rotation Video image rotation clockwise - * @param uri Video stream URI - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_video_stream_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t camera_id,uint8_t status,float framerate,uint16_t resolution_h,uint16_t resolution_v,uint32_t bitrate,uint16_t rotation,const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, resolution_h); - _mav_put_uint16_t(buf, 10, resolution_v); - _mav_put_uint16_t(buf, 12, rotation); - _mav_put_uint8_t(buf, 14, camera_id); - _mav_put_uint8_t(buf, 15, status); - _mav_put_char_array(buf, 16, uri, 230); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN); -#else - mavlink_video_stream_information_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.camera_id = camera_id; - packet.status = status; - mav_array_memcpy(packet.uri, uri, sizeof(char)*230); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -} - -/** - * @brief Encode a video_stream_information struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param video_stream_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_video_stream_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_video_stream_information_t* video_stream_information) -{ - return mavlink_msg_video_stream_information_pack(system_id, component_id, msg, video_stream_information->camera_id, video_stream_information->status, video_stream_information->framerate, video_stream_information->resolution_h, video_stream_information->resolution_v, video_stream_information->bitrate, video_stream_information->rotation, video_stream_information->uri); -} - -/** - * @brief Encode a video_stream_information struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param video_stream_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_video_stream_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_video_stream_information_t* video_stream_information) -{ - return mavlink_msg_video_stream_information_pack_chan(system_id, component_id, chan, msg, video_stream_information->camera_id, video_stream_information->status, video_stream_information->framerate, video_stream_information->resolution_h, video_stream_information->resolution_v, video_stream_information->bitrate, video_stream_information->rotation, video_stream_information->uri); -} - -/** - * @brief Send a video_stream_information message - * @param chan MAVLink channel to send the message - * - * @param camera_id Camera ID (1 for first, 2 for second, etc.) - * @param status Current status of video streaming (0: not running, 1: in progress) - * @param framerate Frames per second - * @param resolution_h Resolution horizontal in pixels - * @param resolution_v Resolution vertical in pixels - * @param bitrate Bit rate in bits per second - * @param rotation Video image rotation clockwise - * @param uri Video stream URI - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_video_stream_information_send(mavlink_channel_t chan, uint8_t camera_id, uint8_t status, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, resolution_h); - _mav_put_uint16_t(buf, 10, resolution_v); - _mav_put_uint16_t(buf, 12, rotation); - _mav_put_uint8_t(buf, 14, camera_id); - _mav_put_uint8_t(buf, 15, status); - _mav_put_char_array(buf, 16, uri, 230); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -#else - mavlink_video_stream_information_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.camera_id = camera_id; - packet.status = status; - mav_array_memcpy(packet.uri, uri, sizeof(char)*230); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -#endif -} - -/** - * @brief Send a video_stream_information message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_video_stream_information_send_struct(mavlink_channel_t chan, const mavlink_video_stream_information_t* video_stream_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_video_stream_information_send(chan, video_stream_information->camera_id, video_stream_information->status, video_stream_information->framerate, video_stream_information->resolution_h, video_stream_information->resolution_v, video_stream_information->bitrate, video_stream_information->rotation, video_stream_information->uri); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, (const char *)video_stream_information, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_video_stream_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t camera_id, uint8_t status, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, resolution_h); - _mav_put_uint16_t(buf, 10, resolution_v); - _mav_put_uint16_t(buf, 12, rotation); - _mav_put_uint8_t(buf, 14, camera_id); - _mav_put_uint8_t(buf, 15, status); - _mav_put_char_array(buf, 16, uri, 230); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -#else - mavlink_video_stream_information_t *packet = (mavlink_video_stream_information_t *)msgbuf; - packet->framerate = framerate; - packet->bitrate = bitrate; - packet->resolution_h = resolution_h; - packet->resolution_v = resolution_v; - packet->rotation = rotation; - packet->camera_id = camera_id; - packet->status = status; - mav_array_memcpy(packet->uri, uri, sizeof(char)*230); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VIDEO_STREAM_INFORMATION UNPACKING - - -/** - * @brief Get field camera_id from video_stream_information message - * - * @return Camera ID (1 for first, 2 for second, etc.) - */ -static inline uint8_t mavlink_msg_video_stream_information_get_camera_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 14); -} - -/** - * @brief Get field status from video_stream_information message - * - * @return Current status of video streaming (0: not running, 1: in progress) - */ -static inline uint8_t mavlink_msg_video_stream_information_get_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 15); -} - -/** - * @brief Get field framerate from video_stream_information message - * - * @return Frames per second - */ -static inline float mavlink_msg_video_stream_information_get_framerate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field resolution_h from video_stream_information message - * - * @return Resolution horizontal in pixels - */ -static inline uint16_t mavlink_msg_video_stream_information_get_resolution_h(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field resolution_v from video_stream_information message - * - * @return Resolution vertical in pixels - */ -static inline uint16_t mavlink_msg_video_stream_information_get_resolution_v(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field bitrate from video_stream_information message - * - * @return Bit rate in bits per second - */ -static inline uint32_t mavlink_msg_video_stream_information_get_bitrate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field rotation from video_stream_information message - * - * @return Video image rotation clockwise - */ -static inline uint16_t mavlink_msg_video_stream_information_get_rotation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field uri from video_stream_information message - * - * @return Video stream URI - */ -static inline uint16_t mavlink_msg_video_stream_information_get_uri(const mavlink_message_t* msg, char *uri) -{ - return _MAV_RETURN_char_array(msg, uri, 230, 16); -} - -/** - * @brief Decode a video_stream_information message into a struct - * - * @param msg The message to decode - * @param video_stream_information C-struct to decode the message contents into - */ -static inline void mavlink_msg_video_stream_information_decode(const mavlink_message_t* msg, mavlink_video_stream_information_t* video_stream_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - video_stream_information->framerate = mavlink_msg_video_stream_information_get_framerate(msg); - video_stream_information->bitrate = mavlink_msg_video_stream_information_get_bitrate(msg); - video_stream_information->resolution_h = mavlink_msg_video_stream_information_get_resolution_h(msg); - video_stream_information->resolution_v = mavlink_msg_video_stream_information_get_resolution_v(msg); - video_stream_information->rotation = mavlink_msg_video_stream_information_get_rotation(msg); - video_stream_information->camera_id = mavlink_msg_video_stream_information_get_camera_id(msg); - video_stream_information->status = mavlink_msg_video_stream_information_get_status(msg); - mavlink_msg_video_stream_information_get_uri(msg, video_stream_information->uri); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN; - memset(video_stream_information, 0, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN); - memcpy(video_stream_information, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_vision_position_estimate.h b/include/mavlink/v2.0/common/mavlink_msg_vision_position_estimate.h deleted file mode 100644 index 0c351e0..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_vision_position_estimate.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE VISION_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102 - -MAVPACKED( -typedef struct __mavlink_vision_position_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X position*/ - float y; /*< Global Y position*/ - float z; /*< Global Z position*/ - float roll; /*< Roll angle in rad*/ - float pitch; /*< Pitch angle in rad*/ - float yaw; /*< Yaw angle in rad*/ -}) mavlink_vision_position_estimate_t; - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN 32 -#define MAVLINK_MSG_ID_102_LEN 32 -#define MAVLINK_MSG_ID_102_MIN_LEN 32 - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC 158 -#define MAVLINK_MSG_ID_102_CRC 158 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ - 102, \ - "VISION_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ - "VISION_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a vision_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Pack a vision_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - 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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - 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, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Encode a vision_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) -{ - return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); -} - -/** - * @brief Encode a vision_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) -{ - return mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); -} - -/** - * @brief Send a vision_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -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[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); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a vision_position_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vision_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_vision_position_estimate_t* vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vision_position_estimate_send(chan, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)vision_position_estimate, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf; - _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_put_float(buf, 20, roll); - _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, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_vision_position_estimate_t *packet = (mavlink_vision_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VISION_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vision_position_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vision_position_estimate message - * - * @return Global X position - */ -static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vision_position_estimate message - * - * @return Global Y position - */ -static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vision_position_estimate message - * - * @return Global Z position - */ -static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from vision_position_estimate message - * - * @return Roll angle in rad - */ -static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from vision_position_estimate message - * - * @return Pitch angle in rad - */ -static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from vision_position_estimate message - * - * @return Yaw angle in rad - */ -static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a vision_position_estimate message into a struct - * - * @param msg The message to decode - * @param vision_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg); - vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg); - vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg); - vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg); - vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg); - 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 - uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN; - memset(vision_position_estimate, 0, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); - memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_vision_speed_estimate.h b/include/mavlink/v2.0/common/mavlink_msg_vision_speed_estimate.h deleted file mode 100644 index bca0947..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_vision_speed_estimate.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE VISION_SPEED_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 - -MAVPACKED( -typedef struct __mavlink_vision_speed_estimate_t { - uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ - float x; /*< Global X speed*/ - float y; /*< Global Y speed*/ - float z; /*< Global Z speed*/ -}) mavlink_vision_speed_estimate_t; - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN 20 -#define MAVLINK_MSG_ID_103_LEN 20 -#define MAVLINK_MSG_ID_103_MIN_LEN 20 - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208 -#define MAVLINK_MSG_ID_103_CRC 208 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ - 103, \ - "VISION_SPEED_ESTIMATE", \ - 4, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ - "VISION_SPEED_ESTIMATE", \ - 4, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ - } \ -} -#endif - -/** - * @brief Pack a vision_speed_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - - 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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -} - -/** - * @brief Pack a vision_speed_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t usec,float x,float y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - - 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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -} - -/** - * @brief Encode a vision_speed_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vision_speed_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ - return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); -} - -/** - * @brief Encode a vision_speed_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vision_speed_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ - return mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, chan, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); -} - -/** - * @brief Send a vision_speed_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - 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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a vision_speed_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vision_speed_estimate_send_struct(mavlink_channel_t chan, const mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vision_speed_estimate_send(chan, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)vision_speed_estimate, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _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, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - mavlink_vision_speed_estimate_t *packet = (mavlink_vision_speed_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VISION_SPEED_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vision_speed_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vision_speed_estimate message - * - * @return Global X speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vision_speed_estimate message - * - * @return Global Y speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vision_speed_estimate message - * - * @return Global Z speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a vision_speed_estimate message into a struct - * - * @param msg The message to decode - * @param vision_speed_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg); - vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg); - vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg); - vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN; - memset(vision_speed_estimate, 0, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); - memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/mavlink_msg_wind_cov.h b/include/mavlink/v2.0/common/mavlink_msg_wind_cov.h deleted file mode 100644 index 0562fb0..0000000 --- a/include/mavlink/v2.0/common/mavlink_msg_wind_cov.h +++ /dev/null @@ -1,413 +0,0 @@ -#pragma once -// MESSAGE WIND_COV PACKING - -#define MAVLINK_MSG_ID_WIND_COV 231 - -MAVPACKED( -typedef struct __mavlink_wind_cov_t { - uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ - float wind_x; /*< Wind in X (NED) direction in m/s*/ - float wind_y; /*< Wind in Y (NED) direction in m/s*/ - float wind_z; /*< Wind in Z (NED) direction in m/s*/ - float var_horiz; /*< Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate.*/ - float var_vert; /*< Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate.*/ - float wind_alt; /*< AMSL altitude (m) this measurement was taken at*/ - float horiz_accuracy; /*< Horizontal speed 1-STD accuracy*/ - float vert_accuracy; /*< Vertical speed 1-STD accuracy*/ -}) mavlink_wind_cov_t; - -#define MAVLINK_MSG_ID_WIND_COV_LEN 40 -#define MAVLINK_MSG_ID_WIND_COV_MIN_LEN 40 -#define MAVLINK_MSG_ID_231_LEN 40 -#define MAVLINK_MSG_ID_231_MIN_LEN 40 - -#define MAVLINK_MSG_ID_WIND_COV_CRC 105 -#define MAVLINK_MSG_ID_231_CRC 105 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_WIND_COV { \ - 231, \ - "WIND_COV", \ - 9, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wind_cov_t, time_usec) }, \ - { "wind_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_cov_t, wind_x) }, \ - { "wind_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_wind_cov_t, wind_y) }, \ - { "wind_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_wind_cov_t, wind_z) }, \ - { "var_horiz", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_wind_cov_t, var_horiz) }, \ - { "var_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_wind_cov_t, var_vert) }, \ - { "wind_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_wind_cov_t, wind_alt) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_wind_cov_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_wind_cov_t, vert_accuracy) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_WIND_COV { \ - "WIND_COV", \ - 9, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wind_cov_t, time_usec) }, \ - { "wind_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_cov_t, wind_x) }, \ - { "wind_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_wind_cov_t, wind_y) }, \ - { "wind_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_wind_cov_t, wind_z) }, \ - { "var_horiz", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_wind_cov_t, var_horiz) }, \ - { "var_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_wind_cov_t, var_vert) }, \ - { "wind_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_wind_cov_t, wind_alt) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_wind_cov_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_wind_cov_t, vert_accuracy) }, \ - } \ -} -#endif - -/** - * @brief Pack a wind_cov 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 (micros since boot or Unix epoch) - * @param wind_x Wind in X (NED) direction in m/s - * @param wind_y Wind in Y (NED) direction in m/s - * @param wind_z Wind in Z (NED) direction in m/s - * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - * @param wind_alt AMSL altitude (m) this measurement was taken at - * @param horiz_accuracy Horizontal speed 1-STD accuracy - * @param vert_accuracy Vertical speed 1-STD accuracy - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wind_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_COV_LEN); -#else - mavlink_wind_cov_t packet; - packet.time_usec = time_usec; - packet.wind_x = wind_x; - packet.wind_y = wind_y; - packet.wind_z = wind_z; - packet.var_horiz = var_horiz; - packet.var_vert = var_vert; - packet.wind_alt = wind_alt; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WIND_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -} - -/** - * @brief Pack a wind_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param wind_x Wind in X (NED) direction in m/s - * @param wind_y Wind in Y (NED) direction in m/s - * @param wind_z Wind in Z (NED) direction in m/s - * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - * @param wind_alt AMSL altitude (m) this measurement was taken at - * @param horiz_accuracy Horizontal speed 1-STD accuracy - * @param vert_accuracy Vertical speed 1-STD accuracy - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wind_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float wind_x,float wind_y,float wind_z,float var_horiz,float var_vert,float wind_alt,float horiz_accuracy,float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_COV_LEN); -#else - mavlink_wind_cov_t packet; - packet.time_usec = time_usec; - packet.wind_x = wind_x; - packet.wind_y = wind_y; - packet.wind_z = wind_z; - packet.var_horiz = var_horiz; - packet.var_vert = var_vert; - packet.wind_alt = wind_alt; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WIND_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -} - -/** - * @brief Encode a wind_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param wind_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wind_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wind_cov_t* wind_cov) -{ - return mavlink_msg_wind_cov_pack(system_id, component_id, msg, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); -} - -/** - * @brief Encode a wind_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param wind_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wind_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wind_cov_t* wind_cov) -{ - return mavlink_msg_wind_cov_pack_chan(system_id, component_id, chan, msg, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); -} - -/** - * @brief Send a wind_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (micros since boot or Unix epoch) - * @param wind_x Wind in X (NED) direction in m/s - * @param wind_y Wind in Y (NED) direction in m/s - * @param wind_z Wind in Z (NED) direction in m/s - * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - * @param wind_alt AMSL altitude (m) this measurement was taken at - * @param horiz_accuracy Horizontal speed 1-STD accuracy - * @param vert_accuracy Vertical speed 1-STD accuracy - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_wind_cov_send(mavlink_channel_t chan, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#else - mavlink_wind_cov_t packet; - packet.time_usec = time_usec; - packet.wind_x = wind_x; - packet.wind_y = wind_y; - packet.wind_z = wind_z; - packet.var_horiz = var_horiz; - packet.var_vert = var_vert; - packet.wind_alt = wind_alt; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)&packet, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#endif -} - -/** - * @brief Send a wind_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_wind_cov_send_struct(mavlink_channel_t chan, const mavlink_wind_cov_t* wind_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_wind_cov_send(chan, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)wind_cov, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_WIND_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_wind_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#else - mavlink_wind_cov_t *packet = (mavlink_wind_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->wind_x = wind_x; - packet->wind_y = wind_y; - packet->wind_z = wind_z; - packet->var_horiz = var_horiz; - packet->var_vert = var_vert; - packet->wind_alt = wind_alt; - packet->horiz_accuracy = horiz_accuracy; - packet->vert_accuracy = vert_accuracy; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)packet, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE WIND_COV UNPACKING - - -/** - * @brief Get field time_usec from wind_cov message - * - * @return Timestamp (micros since boot or Unix epoch) - */ -static inline uint64_t mavlink_msg_wind_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field wind_x from wind_cov message - * - * @return Wind in X (NED) direction in m/s - */ -static inline float mavlink_msg_wind_cov_get_wind_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field wind_y from wind_cov message - * - * @return Wind in Y (NED) direction in m/s - */ -static inline float mavlink_msg_wind_cov_get_wind_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field wind_z from wind_cov message - * - * @return Wind in Z (NED) direction in m/s - */ -static inline float mavlink_msg_wind_cov_get_wind_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field var_horiz from wind_cov message - * - * @return Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - */ -static inline float mavlink_msg_wind_cov_get_var_horiz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field var_vert from wind_cov message - * - * @return Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - */ -static inline float mavlink_msg_wind_cov_get_var_vert(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field wind_alt from wind_cov message - * - * @return AMSL altitude (m) this measurement was taken at - */ -static inline float mavlink_msg_wind_cov_get_wind_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field horiz_accuracy from wind_cov message - * - * @return Horizontal speed 1-STD accuracy - */ -static inline float mavlink_msg_wind_cov_get_horiz_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field vert_accuracy from wind_cov message - * - * @return Vertical speed 1-STD accuracy - */ -static inline float mavlink_msg_wind_cov_get_vert_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a wind_cov message into a struct - * - * @param msg The message to decode - * @param wind_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_wind_cov_decode(const mavlink_message_t* msg, mavlink_wind_cov_t* wind_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - wind_cov->time_usec = mavlink_msg_wind_cov_get_time_usec(msg); - wind_cov->wind_x = mavlink_msg_wind_cov_get_wind_x(msg); - wind_cov->wind_y = mavlink_msg_wind_cov_get_wind_y(msg); - wind_cov->wind_z = mavlink_msg_wind_cov_get_wind_z(msg); - wind_cov->var_horiz = mavlink_msg_wind_cov_get_var_horiz(msg); - wind_cov->var_vert = mavlink_msg_wind_cov_get_var_vert(msg); - wind_cov->wind_alt = mavlink_msg_wind_cov_get_wind_alt(msg); - wind_cov->horiz_accuracy = mavlink_msg_wind_cov_get_horiz_accuracy(msg); - wind_cov->vert_accuracy = mavlink_msg_wind_cov_get_vert_accuracy(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_WIND_COV_LEN? msg->len : MAVLINK_MSG_ID_WIND_COV_LEN; - memset(wind_cov, 0, MAVLINK_MSG_ID_WIND_COV_LEN); - memcpy(wind_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/include/mavlink/v2.0/common/testsuite.h b/include/mavlink/v2.0/common/testsuite.h deleted file mode 100644 index 33efc3c..0000000 --- a/include/mavlink/v2.0/common/testsuite.h +++ /dev/null @@ -1,9195 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from common.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#pragma once -#ifndef COMMON_TESTSUITE_H -#define COMMON_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL - -static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - - mavlink_test_common(system_id, component_id, last_msg); -} -#endif - - - - -static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0); - if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HEARTBEAT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_heartbeat_t packet_in = { - 963497464,17,84,151,218,3 - }; - mavlink_heartbeat_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.custom_mode = packet_in.custom_mode; - packet1.type = packet_in.type; - packet1.autopilot = packet_in.autopilot; - packet1.base_mode = packet_in.base_mode; - packet1.system_status = packet_in.system_status; - packet1.mavlink_version = packet_in.mavlink_version; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SYS_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_sys_status_t packet_in = { - 963497464,963497672,963497880,17859,17963,18067,18171,18275,18379,18483,18587,18691,223 - }; - mavlink_sys_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.onboard_control_sensors_present = packet_in.onboard_control_sensors_present; - packet1.onboard_control_sensors_enabled = packet_in.onboard_control_sensors_enabled; - packet1.onboard_control_sensors_health = packet_in.onboard_control_sensors_health; - packet1.load = packet_in.load; - packet1.voltage_battery = packet_in.voltage_battery; - packet1.current_battery = packet_in.current_battery; - packet1.drop_rate_comm = packet_in.drop_rate_comm; - packet1.errors_comm = packet_in.errors_comm; - packet1.errors_count1 = packet_in.errors_count1; - packet1.errors_count2 = packet_in.errors_count2; - packet1.errors_count3 = packet_in.errors_count3; - packet1.errors_count4 = packet_in.errors_count4; - packet1.battery_remaining = packet_in.battery_remaining; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sys_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_sys_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sys_status_pack(system_id, component_id, &msg , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 ); - mavlink_msg_sys_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sys_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 ); - mavlink_msg_sys_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SYSTEM_TIME >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_system_time_t packet_in = { - 93372036854775807ULL,963497880 - }; - mavlink_system_time_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_unix_usec = packet_in.time_unix_usec; - packet1.time_boot_ms = packet_in.time_boot_ms; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_system_time_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_system_time_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_system_time_pack(system_id, component_id, &msg , packet1.time_unix_usec , packet1.time_boot_ms ); - mavlink_msg_system_time_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_system_time_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_unix_usec , packet1.time_boot_ms ); - mavlink_msg_system_time_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PING >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_ping_t packet_in = { - 93372036854775807ULL,963497880,41,108 - }; - mavlink_ping_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PING_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PING_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ping_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_ping_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ping_pack(system_id, component_id, &msg , packet1.time_usec , packet1.seq , packet1.target_system , packet1.target_component ); - mavlink_msg_ping_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ping_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.seq , packet1.target_system , packet1.target_component ); - mavlink_msg_ping_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_change_operator_control_t packet_in = { - 5,72,139,"DEFGHIJKLMNOPQRSTUVWXYZA" - }; - mavlink_change_operator_control_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.control_request = packet_in.control_request; - packet1.version = packet_in.version; - - mav_array_memcpy(packet1.passkey, packet_in.passkey, sizeof(char)*25); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_change_operator_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey ); - mavlink_msg_change_operator_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey ); - mavlink_msg_change_operator_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_change_operator_control_ack_t packet_in = { - 5,72,139 - }; - mavlink_change_operator_control_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.gcs_system_id = packet_in.gcs_system_id; - packet1.control_request = packet_in.control_request; - packet1.ack = packet_in.ack; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_change_operator_control_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_ack_pack(system_id, component_id, &msg , packet1.gcs_system_id , packet1.control_request , packet1.ack ); - mavlink_msg_change_operator_control_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.gcs_system_id , packet1.control_request , packet1.ack ); - mavlink_msg_change_operator_control_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AUTH_KEY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_auth_key_t packet_in = { - "ABCDEFGHIJKLMNOPQRSTUVWXYZABCDE" - }; - mavlink_auth_key_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - - mav_array_memcpy(packet1.key, packet_in.key, sizeof(char)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_auth_key_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_auth_key_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_auth_key_pack(system_id, component_id, &msg , packet1.key ); - mavlink_msg_auth_key_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_auth_key_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.key ); - mavlink_msg_auth_key_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_MODE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_mode_t packet_in = { - 963497464,17,84 - }; - mavlink_set_mode_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.custom_mode = packet_in.custom_mode; - packet1.target_system = packet_in.target_system; - packet1.base_mode = packet_in.base_mode; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_MODE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_MODE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_mode_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_mode_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_mode_pack(system_id, component_id, &msg , packet1.target_system , packet1.base_mode , packet1.custom_mode ); - mavlink_msg_set_mode_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_mode_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.base_mode , packet1.custom_mode ); - mavlink_msg_set_mode_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_REQUEST_READ >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_request_read_t packet_in = { - 17235,139,206,"EFGHIJKLMNOPQRS" - }; - mavlink_param_request_read_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_index = packet_in.param_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_read_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_read_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index ); - mavlink_msg_param_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_read_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index ); - mavlink_msg_param_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_REQUEST_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_request_list_t packet_in = { - 5,72 - }; - mavlink_param_request_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_param_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_param_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_VALUE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_value_t packet_in = { - 17.0,17443,17547,"IJKLMNOPQRSTUVW",77 - }; - mavlink_param_value_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_value = packet_in.param_value; - packet1.param_count = packet_in.param_count; - packet1.param_index = packet_in.param_index; - packet1.param_type = packet_in.param_type; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_value_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_value_pack(system_id, component_id, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_count , packet1.param_index ); - mavlink_msg_param_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_value_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_count , packet1.param_index ); - mavlink_msg_param_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_SET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_set_t packet_in = { - 17.0,17,84,"GHIJKLMNOPQRSTU",199 - }; - mavlink_param_set_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_value = packet_in.param_value; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.param_type = packet_in.param_type; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_SET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_SET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_set_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_set_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type ); - mavlink_msg_param_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_set_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type ); - mavlink_msg_param_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_RAW_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_raw_int_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,18275,18379,18483,18587,89,156 - }; - mavlink_gps_raw_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.eph = packet_in.eph; - packet1.epv = packet_in.epv; - packet1.vel = packet_in.vel; - packet1.cog = packet_in.cog; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_raw_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_raw_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_raw_int_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible ); - mavlink_msg_gps_raw_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible ); - mavlink_msg_gps_raw_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_status_t packet_in = { - 5,{ 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91 },{ 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151 },{ 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211 },{ 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 },{ 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75 } - }; - mavlink_gps_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.satellites_visible = packet_in.satellites_visible; - - mav_array_memcpy(packet1.satellite_prn, packet_in.satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_used, packet_in.satellite_used, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_elevation, packet_in.satellite_elevation, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_azimuth, packet_in.satellite_azimuth, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_snr, packet_in.satellite_snr, sizeof(uint8_t)*20); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_status_pack(system_id, component_id, &msg , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr ); - mavlink_msg_gps_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr ); - mavlink_msg_gps_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_IMU >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_imu_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275 - }; - mavlink_scaled_imu_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - 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; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RAW_IMU >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_raw_imu_t packet_in = { - 93372036854775807ULL,17651,17755,17859,17963,18067,18171,18275,18379,18483 - }; - mavlink_raw_imu_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - 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; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RAW_IMU_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_IMU_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_imu_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_raw_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_imu_pack(system_id, component_id, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_raw_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_raw_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RAW_PRESSURE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_raw_pressure_t packet_in = { - 93372036854775807ULL,17651,17755,17859,17963 - }; - mavlink_raw_pressure_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff1 = packet_in.press_diff1; - packet1.press_diff2 = packet_in.press_diff2; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_pressure_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_raw_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_pressure_pack(system_id, component_id, &msg , packet1.time_usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature ); - mavlink_msg_raw_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_pressure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature ); - mavlink_msg_raw_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_PRESSURE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_pressure_t packet_in = { - 963497464,45.0,73.0,17859 - }; - mavlink_scaled_pressure_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff = packet_in.press_diff; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0 - }; - mavlink_attitude_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed ); - mavlink_msg_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed ); - mavlink_msg_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE_QUATERNION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_quaternion_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0 - }; - mavlink_attitude_quaternion_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.q1 = packet_in.q1; - packet1.q2 = packet_in.q2; - packet1.q3 = packet_in.q3; - packet1.q4 = packet_in.q4; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed ); - mavlink_msg_attitude_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed ); - mavlink_msg_attitude_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOCAL_POSITION_NED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_local_position_ned_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0 - }; - mavlink_local_position_ned_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_local_position_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz ); - mavlink_msg_local_position_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz ); - mavlink_msg_local_position_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GLOBAL_POSITION_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_global_position_int_t packet_in = { - 963497464,963497672,963497880,963498088,963498296,18275,18379,18483,18587 - }; - mavlink_global_position_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.relative_alt = packet_in.relative_alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.hdg = packet_in.hdg; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_global_position_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg ); - mavlink_msg_global_position_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg ); - mavlink_msg_global_position_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS_SCALED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_scaled_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65,132 - }; - mavlink_rc_channels_scaled_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.chan1_scaled = packet_in.chan1_scaled; - packet1.chan2_scaled = packet_in.chan2_scaled; - packet1.chan3_scaled = packet_in.chan3_scaled; - packet1.chan4_scaled = packet_in.chan4_scaled; - packet1.chan5_scaled = packet_in.chan5_scaled; - packet1.chan6_scaled = packet_in.chan6_scaled; - packet1.chan7_scaled = packet_in.chan7_scaled; - packet1.chan8_scaled = packet_in.chan8_scaled; - packet1.port = packet_in.port; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_scaled_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_scaled_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_scaled_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi ); - mavlink_msg_rc_channels_scaled_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi ); - mavlink_msg_rc_channels_scaled_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_raw_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65,132 - }; - mavlink_rc_channels_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.port = packet_in.port; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_raw_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi ); - mavlink_msg_rc_channels_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi ); - mavlink_msg_rc_channels_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SERVO_OUTPUT_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_servo_output_raw_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65,18327,18431,18535,18639,18743,18847,18951,19055 - }; - mavlink_servo_output_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.servo1_raw = packet_in.servo1_raw; - packet1.servo2_raw = packet_in.servo2_raw; - packet1.servo3_raw = packet_in.servo3_raw; - packet1.servo4_raw = packet_in.servo4_raw; - packet1.servo5_raw = packet_in.servo5_raw; - packet1.servo6_raw = packet_in.servo6_raw; - packet1.servo7_raw = packet_in.servo7_raw; - packet1.servo8_raw = packet_in.servo8_raw; - packet1.port = packet_in.port; - packet1.servo9_raw = packet_in.servo9_raw; - packet1.servo10_raw = packet_in.servo10_raw; - packet1.servo11_raw = packet_in.servo11_raw; - packet1.servo12_raw = packet_in.servo12_raw; - packet1.servo13_raw = packet_in.servo13_raw; - packet1.servo14_raw = packet_in.servo14_raw; - packet1.servo15_raw = packet_in.servo15_raw; - packet1.servo16_raw = packet_in.servo16_raw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_servo_output_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_servo_output_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_servo_output_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw , packet1.servo9_raw , packet1.servo10_raw , packet1.servo11_raw , packet1.servo12_raw , packet1.servo13_raw , packet1.servo14_raw , packet1.servo15_raw , packet1.servo16_raw ); - mavlink_msg_servo_output_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw , packet1.servo9_raw , packet1.servo10_raw , packet1.servo11_raw , packet1.servo12_raw , packet1.servo13_raw , packet1.servo14_raw , packet1.servo15_raw , packet1.servo16_raw ); - mavlink_msg_servo_output_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_partial_list_t packet_in = { - 17235,17339,17,84,151 - }; - mavlink_mission_request_partial_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.start_index = packet_in.start_index; - packet1.end_index = packet_in.end_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_partial_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_partial_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index , packet1.mission_type ); - mavlink_msg_mission_request_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index , packet1.mission_type ); - mavlink_msg_mission_request_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_write_partial_list_t packet_in = { - 17235,17339,17,84,151 - }; - mavlink_mission_write_partial_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.start_index = packet_in.start_index; - packet1.end_index = packet_in.end_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_write_partial_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_write_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_write_partial_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index , packet1.mission_type ); - mavlink_msg_mission_write_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index , packet1.mission_type ); - mavlink_msg_mission_write_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ITEM >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_item_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,18691,18795,101,168,235,46,113,180 - }; - mavlink_mission_item_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.seq = packet_in.seq; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - packet1.current = packet_in.current; - packet1.autocontinue = packet_in.autocontinue; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_item_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z , packet1.mission_type ); - mavlink_msg_mission_item_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z , packet1.mission_type ); - mavlink_msg_mission_item_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_t packet_in = { - 17235,139,206,17 - }; - mavlink_mission_request_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.mission_type ); - mavlink_msg_mission_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.mission_type ); - mavlink_msg_mission_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_SET_CURRENT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_set_current_t packet_in = { - 17235,139,206 - }; - mavlink_mission_set_current_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_set_current_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_set_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_set_current_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq ); - mavlink_msg_mission_set_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_set_current_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq ); - mavlink_msg_mission_set_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_CURRENT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_current_t packet_in = { - 17235 - }; - mavlink_mission_current_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_current_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_current_pack(system_id, component_id, &msg , packet1.seq ); - mavlink_msg_mission_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_current_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seq ); - mavlink_msg_mission_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_list_t packet_in = { - 5,72,139 - }; - mavlink_mission_request_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mission_type ); - mavlink_msg_mission_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mission_type ); - mavlink_msg_mission_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_COUNT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_count_t packet_in = { - 17235,139,206,17 - }; - mavlink_mission_count_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.count = packet_in.count; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_count_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_count_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_count_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.count , packet1.mission_type ); - mavlink_msg_mission_count_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_count_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.count , packet1.mission_type ); - mavlink_msg_mission_count_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_CLEAR_ALL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_clear_all_t packet_in = { - 5,72,139 - }; - mavlink_mission_clear_all_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_clear_all_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_clear_all_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_clear_all_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mission_type ); - mavlink_msg_mission_clear_all_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mission_type ); - mavlink_msg_mission_clear_all_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ITEM_REACHED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_item_reached_t packet_in = { - 17235 - }; - mavlink_mission_item_reached_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_reached_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_item_reached_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_reached_pack(system_id, component_id, &msg , packet1.seq ); - mavlink_msg_mission_item_reached_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seq ); - mavlink_msg_mission_item_reached_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_ack_t packet_in = { - 5,72,139,206 - }; - mavlink_mission_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.type = packet_in.type; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_ack_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.type , packet1.mission_type ); - mavlink_msg_mission_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.type , packet1.mission_type ); - mavlink_msg_mission_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_gps_global_origin_t packet_in = { - 963497464,963497672,963497880,41 - }; - mavlink_set_gps_global_origin_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - packet1.target_system = packet_in.target_system; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_gps_global_origin_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_gps_global_origin_pack(system_id, component_id, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude ); - mavlink_msg_set_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_gps_global_origin_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude ); - mavlink_msg_set_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_global_origin_t packet_in = { - 963497464,963497672,963497880 - }; - mavlink_gps_global_origin_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_global_origin_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_global_origin_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.altitude ); - mavlink_msg_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.altitude ); - mavlink_msg_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_MAP_RC >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_map_rc_t packet_in = { - 17.0,45.0,73.0,101.0,18067,187,254,"UVWXYZABCDEFGHI",113 - }; - mavlink_param_map_rc_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_value0 = packet_in.param_value0; - packet1.scale = packet_in.scale; - packet1.param_value_min = packet_in.param_value_min; - packet1.param_value_max = packet_in.param_value_max; - packet1.param_index = packet_in.param_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.parameter_rc_channel_index = packet_in.parameter_rc_channel_index; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_map_rc_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_map_rc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_map_rc_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index , packet1.parameter_rc_channel_index , packet1.param_value0 , packet1.scale , packet1.param_value_min , packet1.param_value_max ); - mavlink_msg_param_map_rc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_map_rc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index , packet1.parameter_rc_channel_index , packet1.param_value0 , packet1.scale , packet1.param_value_min , packet1.param_value_max ); - mavlink_msg_param_map_rc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_int_t packet_in = { - 17235,139,206,17 - }; - mavlink_mission_request_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_int_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.mission_type ); - mavlink_msg_mission_request_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.mission_type ); - mavlink_msg_mission_request_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_safety_set_allowed_area_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,77,144,211 - }; - mavlink_safety_set_allowed_area_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.p1x = packet_in.p1x; - packet1.p1y = packet_in.p1y; - packet1.p1z = packet_in.p1z; - packet1.p2x = packet_in.p2x; - packet1.p2y = packet_in.p2y; - packet1.p2z = packet_in.p2z; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_set_allowed_area_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_safety_allowed_area_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,77 - }; - mavlink_safety_allowed_area_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.p1x = packet_in.p1x; - packet1.p1y = packet_in.p1y; - packet1.p1z = packet_in.p1z; - packet1.p2x = packet_in.p2x; - packet1.p2y = packet_in.p2y; - packet1.p2z = packet_in.p2z; - packet1.frame = packet_in.frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_allowed_area_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_safety_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_allowed_area_pack(system_id, component_id, &msg , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_quaternion_cov_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0 },185.0,213.0,241.0,{ 269.0, 270.0, 271.0, 272.0, 273.0, 274.0, 275.0, 276.0, 277.0 } - }; - mavlink_attitude_quaternion_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*9); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.q , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.covariance ); - mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.q , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.covariance ); - mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_nav_controller_output_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,18275,18379,18483 - }; - mavlink_nav_controller_output_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.nav_roll = packet_in.nav_roll; - packet1.nav_pitch = packet_in.nav_pitch; - packet1.alt_error = packet_in.alt_error; - packet1.aspd_error = packet_in.aspd_error; - packet1.xtrack_error = packet_in.xtrack_error; - packet1.nav_bearing = packet_in.nav_bearing; - packet1.target_bearing = packet_in.target_bearing; - packet1.wp_dist = packet_in.wp_dist; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_nav_controller_output_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_nav_controller_output_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_nav_controller_output_pack(system_id, component_id, &msg , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error ); - mavlink_msg_nav_controller_output_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error ); - mavlink_msg_nav_controller_output_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_global_position_int_cov_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,963498504,185.0,213.0,241.0,{ 269.0, 270.0, 271.0, 272.0, 273.0, 274.0, 275.0, 276.0, 277.0, 278.0, 279.0, 280.0, 281.0, 282.0, 283.0, 284.0, 285.0, 286.0, 287.0, 288.0, 289.0, 290.0, 291.0, 292.0, 293.0, 294.0, 295.0, 296.0, 297.0, 298.0, 299.0, 300.0, 301.0, 302.0, 303.0, 304.0 },33 - }; - mavlink_global_position_int_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.relative_alt = packet_in.relative_alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.estimator_type = packet_in.estimator_type; - - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*36); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_global_position_int_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.estimator_type , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.covariance ); - mavlink_msg_global_position_int_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.estimator_type , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.covariance ); - mavlink_msg_global_position_int_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_local_position_ned_cov_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,{ 325.0, 326.0, 327.0, 328.0, 329.0, 330.0, 331.0, 332.0, 333.0, 334.0, 335.0, 336.0, 337.0, 338.0, 339.0, 340.0, 341.0, 342.0, 343.0, 344.0, 345.0, 346.0, 347.0, 348.0, 349.0, 350.0, 351.0, 352.0, 353.0, 354.0, 355.0, 356.0, 357.0, 358.0, 359.0, 360.0, 361.0, 362.0, 363.0, 364.0, 365.0, 366.0, 367.0, 368.0, 369.0 },165 - }; - mavlink_local_position_ned_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.ax = packet_in.ax; - packet1.ay = packet_in.ay; - packet1.az = packet_in.az; - packet1.estimator_type = packet_in.estimator_type; - - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*45); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_local_position_ned_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.estimator_type , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az , packet1.covariance ); - mavlink_msg_local_position_ned_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.estimator_type , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az , packet1.covariance ); - mavlink_msg_local_position_ned_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275,18379,18483,18587,18691,18795,18899,19003,19107,19211,125,192 - }; - mavlink_rc_channels_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.chan9_raw = packet_in.chan9_raw; - packet1.chan10_raw = packet_in.chan10_raw; - packet1.chan11_raw = packet_in.chan11_raw; - packet1.chan12_raw = packet_in.chan12_raw; - packet1.chan13_raw = packet_in.chan13_raw; - packet1.chan14_raw = packet_in.chan14_raw; - packet1.chan15_raw = packet_in.chan15_raw; - packet1.chan16_raw = packet_in.chan16_raw; - packet1.chan17_raw = packet_in.chan17_raw; - packet1.chan18_raw = packet_in.chan18_raw; - packet1.chancount = packet_in.chancount; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.chancount , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.chan13_raw , packet1.chan14_raw , packet1.chan15_raw , packet1.chan16_raw , packet1.chan17_raw , packet1.chan18_raw , packet1.rssi ); - mavlink_msg_rc_channels_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.chancount , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.chan13_raw , packet1.chan14_raw , packet1.chan15_raw , packet1.chan16_raw , packet1.chan17_raw , packet1.chan18_raw , packet1.rssi ); - mavlink_msg_rc_channels_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_REQUEST_DATA_STREAM >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_request_data_stream_t packet_in = { - 17235,139,206,17,84 - }; - mavlink_request_data_stream_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.req_message_rate = packet_in.req_message_rate; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.req_stream_id = packet_in.req_stream_id; - packet1.start_stop = packet_in.start_stop; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_data_stream_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_request_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_data_stream_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop ); - mavlink_msg_request_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_data_stream_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop ); - mavlink_msg_request_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DATA_STREAM >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_data_stream_t packet_in = { - 17235,139,206 - }; - mavlink_data_stream_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.message_rate = packet_in.message_rate; - packet1.stream_id = packet_in.stream_id; - packet1.on_off = packet_in.on_off; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_stream_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_stream_pack(system_id, component_id, &msg , packet1.stream_id , packet1.message_rate , packet1.on_off ); - mavlink_msg_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_stream_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.stream_id , packet1.message_rate , packet1.on_off ); - mavlink_msg_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MANUAL_CONTROL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_manual_control_t packet_in = { - 17235,17339,17443,17547,17651,163 - }; - mavlink_manual_control_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.r = packet_in.r; - packet1.buttons = packet_in.buttons; - packet1.target = packet_in.target; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_control_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_control_pack(system_id, component_id, &msg , packet1.target , packet1.x , packet1.y , packet1.z , packet1.r , packet1.buttons ); - mavlink_msg_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target , packet1.x , packet1.y , packet1.z , packet1.r , packet1.buttons ); - mavlink_msg_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_override_t packet_in = { - 17235,17339,17443,17547,17651,17755,17859,17963,53,120 - }; - mavlink_rc_channels_override_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_override_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_override_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_override_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw ); - mavlink_msg_rc_channels_override_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw ); - mavlink_msg_rc_channels_override_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ITEM_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_item_int_t packet_in = { - 17.0,45.0,73.0,101.0,963498296,963498504,185.0,18691,18795,101,168,235,46,113,180 - }; - mavlink_mission_item_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.seq = packet_in.seq; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - packet1.current = packet_in.current; - packet1.autocontinue = packet_in.autocontinue; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_item_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_int_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z , packet1.mission_type ); - mavlink_msg_mission_item_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z , packet1.mission_type ); - mavlink_msg_mission_item_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VFR_HUD >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vfr_hud_t packet_in = { - 17.0,45.0,73.0,101.0,18067,18171 - }; - mavlink_vfr_hud_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.airspeed = packet_in.airspeed; - packet1.groundspeed = packet_in.groundspeed; - packet1.alt = packet_in.alt; - packet1.climb = packet_in.climb; - packet1.heading = packet_in.heading; - packet1.throttle = packet_in.throttle; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VFR_HUD_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VFR_HUD_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vfr_hud_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vfr_hud_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vfr_hud_pack(system_id, component_id, &msg , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb ); - mavlink_msg_vfr_hud_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vfr_hud_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb ); - mavlink_msg_vfr_hud_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMMAND_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_command_int_t packet_in = { - 17.0,45.0,73.0,101.0,963498296,963498504,185.0,18691,223,34,101,168,235 - }; - mavlink_command_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - packet1.current = packet_in.current; - packet1.autocontinue = packet_in.autocontinue; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_command_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_int_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z ); - mavlink_msg_command_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z ); - mavlink_msg_command_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMMAND_LONG >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_command_long_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,18691,223,34,101 - }; - mavlink_command_long_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.param5 = packet_in.param5; - packet1.param6 = packet_in.param6; - packet1.param7 = packet_in.param7; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.confirmation = packet_in.confirmation; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_long_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_command_long_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_long_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.param5 , packet1.param6 , packet1.param7 ); - mavlink_msg_command_long_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_long_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.param5 , packet1.param6 , packet1.param7 ); - mavlink_msg_command_long_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMMAND_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_command_ack_t packet_in = { - 17235,139 - }; - mavlink_command_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.command = packet_in.command; - packet1.result = packet_in.result; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_command_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_ack_pack(system_id, component_id, &msg , packet1.command , packet1.result ); - mavlink_msg_command_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command , packet1.result ); - mavlink_msg_command_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MANUAL_SETPOINT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_manual_setpoint_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,65,132 - }; - mavlink_manual_setpoint_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.thrust = packet_in.thrust; - packet1.mode_switch = packet_in.mode_switch; - packet1.manual_override_switch = packet_in.manual_override_switch; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_setpoint_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_manual_setpoint_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_setpoint_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch ); - mavlink_msg_manual_setpoint_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch ); - mavlink_msg_manual_setpoint_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_ATTITUDE_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_attitude_target_t packet_in = { - 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,241.0,113,180,247 - }; - mavlink_set_attitude_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.body_roll_rate = packet_in.body_roll_rate; - packet1.body_pitch_rate = packet_in.body_pitch_rate; - packet1.body_yaw_rate = packet_in.body_yaw_rate; - packet1.thrust = packet_in.thrust; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.type_mask = packet_in.type_mask; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_attitude_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_attitude_target_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); - mavlink_msg_set_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_attitude_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); - mavlink_msg_set_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_target_t packet_in = { - 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,241.0,113 - }; - mavlink_attitude_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.body_roll_rate = packet_in.body_roll_rate; - packet1.body_pitch_rate = packet_in.body_pitch_rate; - packet1.body_yaw_rate = packet_in.body_yaw_rate; - packet1.thrust = packet_in.thrust; - packet1.type_mask = packet_in.type_mask; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_target_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); - mavlink_msg_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); - mavlink_msg_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_position_target_local_ned_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27,94,161 - }; - mavlink_set_position_target_local_ned_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_local_ned_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_position_target_local_ned_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27 - }; - mavlink_position_target_local_ned_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_local_ned_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_position_target_global_int_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27,94,161 - }; - mavlink_set_position_target_global_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat_int = packet_in.lat_int; - packet1.lon_int = packet_in.lon_int; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_global_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_position_target_global_int_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27 - }; - mavlink_position_target_global_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat_int = packet_in.lat_int; - packet1.lon_int = packet_in.lon_int; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_global_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_local_position_ned_system_global_offset_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0 - }; - mavlink_local_position_ned_system_global_offset_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_system_global_offset_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_state_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,963499128,963499336,963499544,19523,19627,19731,19835,19939,20043 - }; - mavlink_hil_state_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.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_pack(system_id, component_id, &msg , packet1.time_usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_CONTROLS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_controls_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,125,192 - }; - mavlink_hil_controls_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.roll_ailerons = packet_in.roll_ailerons; - packet1.pitch_elevator = packet_in.pitch_elevator; - packet1.yaw_rudder = packet_in.yaw_rudder; - packet1.throttle = packet_in.throttle; - packet1.aux1 = packet_in.aux1; - packet1.aux2 = packet_in.aux2; - packet1.aux3 = packet_in.aux3; - packet1.aux4 = packet_in.aux4; - packet1.mode = packet_in.mode; - packet1.nav_mode = packet_in.nav_mode; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_controls_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_controls_pack(system_id, component_id, &msg , packet1.time_usec , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.aux1 , packet1.aux2 , packet1.aux3 , packet1.aux4 , packet1.mode , packet1.nav_mode ); - mavlink_msg_hil_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_controls_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.aux1 , packet1.aux2 , packet1.aux3 , packet1.aux4 , packet1.mode , packet1.nav_mode ); - mavlink_msg_hil_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_rc_inputs_raw_t packet_in = { - 93372036854775807ULL,17651,17755,17859,17963,18067,18171,18275,18379,18483,18587,18691,18795,101 - }; - mavlink_hil_rc_inputs_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.chan9_raw = packet_in.chan9_raw; - packet1.chan10_raw = packet_in.chan10_raw; - packet1.chan11_raw = packet_in.chan11_raw; - packet1.chan12_raw = packet_in.chan12_raw; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_rc_inputs_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.rssi ); - mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.rssi ); - mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_actuator_controls_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,{ 129.0, 130.0, 131.0, 132.0, 133.0, 134.0, 135.0, 136.0, 137.0, 138.0, 139.0, 140.0, 141.0, 142.0, 143.0, 144.0 },245 - }; - mavlink_hil_actuator_controls_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.flags = packet_in.flags; - packet1.mode = packet_in.mode; - - mav_array_memcpy(packet1.controls, packet_in.controls, sizeof(float)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_actuator_controls_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_actuator_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_actuator_controls_pack(system_id, component_id, &msg , packet1.time_usec , packet1.controls , packet1.mode , packet1.flags ); - mavlink_msg_hil_actuator_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_actuator_controls_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.controls , packet1.mode , packet1.flags ); - mavlink_msg_hil_actuator_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPTICAL_FLOW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_optical_flow_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,18275,18379,77,144,199.0,227.0 - }; - mavlink_optical_flow_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.flow_comp_m_x = packet_in.flow_comp_m_x; - packet1.flow_comp_m_y = packet_in.flow_comp_m_y; - packet1.ground_distance = packet_in.ground_distance; - packet1.flow_x = packet_in.flow_x; - packet1.flow_y = packet_in.flow_y; - packet1.sensor_id = packet_in.sensor_id; - packet1.quality = packet_in.quality; - packet1.flow_rate_x = packet_in.flow_rate_x; - packet1.flow_rate_y = packet_in.flow_rate_y; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance , packet1.flow_rate_x , packet1.flow_rate_y ); - mavlink_msg_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance , packet1.flow_rate_x , packet1.flow_rate_y ); - mavlink_msg_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_global_vision_position_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0 - }; - mavlink_global_vision_position_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_vision_position_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vision_position_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0 - }; - mavlink_vision_position_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vision_speed_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0 - }; - mavlink_vision_speed_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_speed_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vision_speed_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_speed_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z ); - mavlink_msg_vision_speed_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z ); - mavlink_msg_vision_speed_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vicon_position_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0 - }; - mavlink_vicon_position_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vicon_position_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vicon_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vicon_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_vicon_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_vicon_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIGHRES_IMU >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_highres_imu_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,20355 - }; - mavlink_highres_imu_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - 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.temperature = packet_in.temperature; - packet1.fields_updated = packet_in.fields_updated; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_highres_imu_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_highres_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_highres_imu_pack(system_id, component_id, &msg , packet1.time_usec , 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.temperature , packet1.fields_updated ); - mavlink_msg_highres_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_highres_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , 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.temperature , packet1.fields_updated ); - mavlink_msg_highres_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPTICAL_FLOW_RAD >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_optical_flow_rad_t packet_in = { - 93372036854775807ULL,963497880,101.0,129.0,157.0,185.0,213.0,963499128,269.0,19315,3,70 - }; - mavlink_optical_flow_rad_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.integration_time_us = packet_in.integration_time_us; - packet1.integrated_x = packet_in.integrated_x; - packet1.integrated_y = packet_in.integrated_y; - packet1.integrated_xgyro = packet_in.integrated_xgyro; - packet1.integrated_ygyro = packet_in.integrated_ygyro; - packet1.integrated_zgyro = packet_in.integrated_zgyro; - packet1.time_delta_distance_us = packet_in.time_delta_distance_us; - packet1.distance = packet_in.distance; - packet1.temperature = packet_in.temperature; - packet1.sensor_id = packet_in.sensor_id; - packet1.quality = packet_in.quality; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_rad_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_optical_flow_rad_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_rad_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_optical_flow_rad_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_rad_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_optical_flow_rad_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_SENSOR >= 256) { - return; - } -#endif - 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,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,963500584 - }; - mavlink_hil_sensor_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - 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.temperature = packet_in.temperature; - packet1.fields_updated = packet_in.fields_updated; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN); - } -#endif - 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.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.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.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.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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SIM_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_sim_state_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,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 - }; - mavlink_sim_state_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.q1 = packet_in.q1; - packet1.q2 = packet_in.q2; - packet1.q3 = packet_in.q3; - packet1.q4 = packet_in.q4; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - 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.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.std_dev_horz = packet_in.std_dev_horz; - packet1.std_dev_vert = packet_in.std_dev_vert; - packet1.vn = packet_in.vn; - packet1.ve = packet_in.ve; - packet1.vd = packet_in.vd; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SIM_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SIM_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sim_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_sim_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sim_state_pack(system_id, component_id, &msg , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.lat , packet1.lon , packet1.alt , packet1.std_dev_horz , packet1.std_dev_vert , packet1.vn , packet1.ve , packet1.vd ); - mavlink_msg_sim_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sim_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.lat , packet1.lon , packet1.alt , packet1.std_dev_horz , packet1.std_dev_vert , packet1.vn , packet1.ve , packet1.vd ); - mavlink_msg_sim_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RADIO_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_radio_status_t packet_in = { - 17235,17339,17,84,151,218,29 - }; - mavlink_radio_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.rxerrors = packet_in.rxerrors; - packet1.fixed = packet_in.fixed; - packet1.rssi = packet_in.rssi; - packet1.remrssi = packet_in.remrssi; - packet1.txbuf = packet_in.txbuf; - packet1.noise = packet_in.noise; - packet1.remnoise = packet_in.remnoise; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_radio_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_radio_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_radio_status_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed ); - mavlink_msg_radio_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_radio_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed ); - mavlink_msg_radio_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_file_transfer_protocol_t packet_in = { - 5,72,139,{ 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200 } - }; - mavlink_file_transfer_protocol_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_network = packet_in.target_network; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.payload, packet_in.payload, sizeof(uint8_t)*251); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_file_transfer_protocol_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_file_transfer_protocol_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_file_transfer_protocol_pack(system_id, component_id, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.payload ); - mavlink_msg_file_transfer_protocol_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.payload ); - mavlink_msg_file_transfer_protocol_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TIMESYNC >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_timesync_t packet_in = { - 93372036854775807LL,93372036854776311LL - }; - mavlink_timesync_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.tc1 = packet_in.tc1; - packet1.ts1 = packet_in.ts1; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TIMESYNC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TIMESYNC_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_timesync_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_timesync_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_timesync_pack(system_id, component_id, &msg , packet1.tc1 , packet1.ts1 ); - mavlink_msg_timesync_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_timesync_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.tc1 , packet1.ts1 ); - mavlink_msg_timesync_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_TRIGGER >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_trigger_t packet_in = { - 93372036854775807ULL,963497880 - }; - mavlink_camera_trigger_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.seq = packet_in.seq; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_trigger_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_trigger_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_trigger_pack(system_id, component_id, &msg , packet1.time_usec , packet1.seq ); - mavlink_msg_camera_trigger_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_trigger_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.seq ); - mavlink_msg_camera_trigger_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_GPS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_gps_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,18275,18379,18483,18587,18691,18795,18899,235,46 - }; - mavlink_hil_gps_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.eph = packet_in.eph; - packet1.epv = packet_in.epv; - packet1.vel = packet_in.vel; - packet1.vn = packet_in.vn; - packet1.ve = packet_in.ve; - packet1.vd = packet_in.vd; - packet1.cog = packet_in.cog; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_GPS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_GPS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_gps_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_gps_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_gps_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.vn , packet1.ve , packet1.vd , packet1.cog , packet1.satellites_visible ); - mavlink_msg_hil_gps_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_gps_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.vn , packet1.ve , packet1.vd , packet1.cog , packet1.satellites_visible ); - mavlink_msg_hil_gps_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_OPTICAL_FLOW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_optical_flow_t packet_in = { - 93372036854775807ULL,963497880,101.0,129.0,157.0,185.0,213.0,963499128,269.0,19315,3,70 - }; - mavlink_hil_optical_flow_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.integration_time_us = packet_in.integration_time_us; - packet1.integrated_x = packet_in.integrated_x; - packet1.integrated_y = packet_in.integrated_y; - packet1.integrated_xgyro = packet_in.integrated_xgyro; - packet1.integrated_ygyro = packet_in.integrated_ygyro; - packet1.integrated_zgyro = packet_in.integrated_zgyro; - packet1.time_delta_distance_us = packet_in.time_delta_distance_us; - packet1.distance = packet_in.distance; - packet1.temperature = packet_in.temperature; - packet1.sensor_id = packet_in.sensor_id; - packet1.quality = packet_in.quality; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_optical_flow_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_hil_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_hil_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_STATE_QUATERNION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_state_quaternion_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0 },185.0,213.0,241.0,963499336,963499544,963499752,19731,19835,19939,20043,20147,20251,20355,20459 - }; - mavlink_hil_state_quaternion_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.ind_airspeed = packet_in.ind_airspeed; - packet1.true_airspeed = packet_in.true_airspeed; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - - mav_array_memcpy(packet1.attitude_quaternion, packet_in.attitude_quaternion, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_quaternion_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_state_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_quaternion_pack(system_id, component_id, &msg , packet1.time_usec , packet1.attitude_quaternion , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.ind_airspeed , packet1.true_airspeed , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.attitude_quaternion , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.ind_airspeed , packet1.true_airspeed , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_IMU2 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_imu2_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275 - }; - mavlink_scaled_imu2_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - 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; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu2_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_imu2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu2_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_REQUEST_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_request_list_t packet_in = { - 17235,17339,17,84 - }; - mavlink_log_request_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.start = packet_in.start; - packet1.end = packet_in.end; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.start , packet1.end ); - mavlink_msg_log_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.start , packet1.end ); - mavlink_msg_log_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_ENTRY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_entry_t packet_in = { - 963497464,963497672,17651,17755,17859 - }; - mavlink_log_entry_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_utc = packet_in.time_utc; - packet1.size = packet_in.size; - packet1.id = packet_in.id; - packet1.num_logs = packet_in.num_logs; - packet1.last_log_num = packet_in.last_log_num; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_entry_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_entry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_entry_pack(system_id, component_id, &msg , packet1.id , packet1.num_logs , packet1.last_log_num , packet1.time_utc , packet1.size ); - mavlink_msg_log_entry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_entry_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.num_logs , packet1.last_log_num , packet1.time_utc , packet1.size ); - mavlink_msg_log_entry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_REQUEST_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_request_data_t packet_in = { - 963497464,963497672,17651,163,230 - }; - mavlink_log_request_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.ofs = packet_in.ofs; - packet1.count = packet_in.count; - packet1.id = packet_in.id; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_request_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_data_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id , packet1.ofs , packet1.count ); - mavlink_msg_log_request_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id , packet1.ofs , packet1.count ); - mavlink_msg_log_request_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_data_t packet_in = { - 963497464,17443,151,{ 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51 } - }; - mavlink_log_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.ofs = packet_in.ofs; - packet1.id = packet_in.id; - packet1.count = packet_in.count; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*90); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_data_pack(system_id, component_id, &msg , packet1.id , packet1.ofs , packet1.count , packet1.data ); - mavlink_msg_log_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.ofs , packet1.count , packet1.data ); - mavlink_msg_log_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_ERASE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_erase_t packet_in = { - 5,72 - }; - mavlink_log_erase_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_erase_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_erase_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_erase_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_erase_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_erase_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_erase_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_REQUEST_END >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_request_end_t packet_in = { - 5,72 - }; - mavlink_log_request_end_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_end_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_request_end_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_end_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_request_end_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_end_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_request_end_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_INJECT_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_inject_data_t packet_in = { - 5,72,139,{ 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59 } - }; - mavlink_gps_inject_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.len = packet_in.len; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*110); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_inject_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_inject_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_inject_data_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.len , packet1.data ); - mavlink_msg_gps_inject_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.len , packet1.data ); - mavlink_msg_gps_inject_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS2_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps2_raw_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,963498504,18483,18587,18691,18795,101,168,235 - }; - mavlink_gps2_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.dgps_age = packet_in.dgps_age; - packet1.eph = packet_in.eph; - packet1.epv = packet_in.epv; - packet1.vel = packet_in.vel; - packet1.cog = packet_in.cog; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - packet1.dgps_numch = packet_in.dgps_numch; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps2_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.dgps_numch , packet1.dgps_age ); - mavlink_msg_gps2_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.dgps_numch , packet1.dgps_age ); - mavlink_msg_gps2_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_POWER_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_power_status_t packet_in = { - 17235,17339,17443 - }; - mavlink_power_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.Vcc = packet_in.Vcc; - packet1.Vservo = packet_in.Vservo; - packet1.flags = packet_in.flags; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_power_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_power_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_power_status_pack(system_id, component_id, &msg , packet1.Vcc , packet1.Vservo , packet1.flags ); - mavlink_msg_power_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_power_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Vcc , packet1.Vservo , packet1.flags ); - mavlink_msg_power_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SERIAL_CONTROL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_serial_control_t packet_in = { - 963497464,17443,151,218,29,{ 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165 } - }; - mavlink_serial_control_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.baudrate = packet_in.baudrate; - packet1.timeout = packet_in.timeout; - packet1.device = packet_in.device; - packet1.flags = packet_in.flags; - packet1.count = packet_in.count; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*70); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_serial_control_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_serial_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_serial_control_pack(system_id, component_id, &msg , packet1.device , packet1.flags , packet1.timeout , packet1.baudrate , packet1.count , packet1.data ); - mavlink_msg_serial_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_serial_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.device , packet1.flags , packet1.timeout , packet1.baudrate , packet1.count , packet1.data ); - mavlink_msg_serial_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_RTK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_rtk_t packet_in = { - 963497464,963497672,963497880,963498088,963498296,963498504,963498712,18691,223,34,101,168,235 - }; - mavlink_gps_rtk_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_last_baseline_ms = packet_in.time_last_baseline_ms; - packet1.tow = packet_in.tow; - packet1.baseline_a_mm = packet_in.baseline_a_mm; - packet1.baseline_b_mm = packet_in.baseline_b_mm; - packet1.baseline_c_mm = packet_in.baseline_c_mm; - packet1.accuracy = packet_in.accuracy; - packet1.iar_num_hypotheses = packet_in.iar_num_hypotheses; - packet1.wn = packet_in.wn; - packet1.rtk_receiver_id = packet_in.rtk_receiver_id; - packet1.rtk_health = packet_in.rtk_health; - packet1.rtk_rate = packet_in.rtk_rate; - packet1.nsats = packet_in.nsats; - packet1.baseline_coords_type = packet_in.baseline_coords_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_RTK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_RTK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtk_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtk_pack(system_id, component_id, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtk_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS2_RTK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps2_rtk_t packet_in = { - 963497464,963497672,963497880,963498088,963498296,963498504,963498712,18691,223,34,101,168,235 - }; - mavlink_gps2_rtk_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_last_baseline_ms = packet_in.time_last_baseline_ms; - packet1.tow = packet_in.tow; - packet1.baseline_a_mm = packet_in.baseline_a_mm; - packet1.baseline_b_mm = packet_in.baseline_b_mm; - packet1.baseline_c_mm = packet_in.baseline_c_mm; - packet1.accuracy = packet_in.accuracy; - packet1.iar_num_hypotheses = packet_in.iar_num_hypotheses; - packet1.wn = packet_in.wn; - packet1.rtk_receiver_id = packet_in.rtk_receiver_id; - packet1.rtk_health = packet_in.rtk_health; - packet1.rtk_rate = packet_in.rtk_rate; - packet1.nsats = packet_in.nsats; - packet1.baseline_coords_type = packet_in.baseline_coords_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_rtk_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps2_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_rtk_pack(system_id, component_id, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps2_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_rtk_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps2_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_IMU3 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_imu3_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275 - }; - mavlink_scaled_imu3_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - 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; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu3_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_imu3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu3_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu3_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag ); - mavlink_msg_scaled_imu3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_data_transmission_handshake_t packet_in = { - 963497464,17443,17547,17651,163,230,41 - }; - mavlink_data_transmission_handshake_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.size = packet_in.size; - packet1.width = packet_in.width; - packet1.height = packet_in.height; - packet1.packets = packet_in.packets; - packet1.type = packet_in.type; - packet1.payload = packet_in.payload; - packet1.jpg_quality = packet_in.jpg_quality; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_transmission_handshake_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_data_transmission_handshake_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_transmission_handshake_pack(system_id, component_id, &msg , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality ); - mavlink_msg_data_transmission_handshake_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality ); - mavlink_msg_data_transmission_handshake_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ENCAPSULATED_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_encapsulated_data_t packet_in = { - 17235,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135 } - }; - mavlink_encapsulated_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seqnr = packet_in.seqnr; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*253); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_encapsulated_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_encapsulated_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_encapsulated_data_pack(system_id, component_id, &msg , packet1.seqnr , packet1.data ); - mavlink_msg_encapsulated_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seqnr , packet1.data ); - mavlink_msg_encapsulated_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DISTANCE_SENSOR >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_distance_sensor_t packet_in = { - 963497464,17443,17547,17651,163,230,41,108 - }; - mavlink_distance_sensor_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.min_distance = packet_in.min_distance; - packet1.max_distance = packet_in.max_distance; - packet1.current_distance = packet_in.current_distance; - packet1.type = packet_in.type; - packet1.id = packet_in.id; - packet1.orientation = packet_in.orientation; - packet1.covariance = packet_in.covariance; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_distance_sensor_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_distance_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_distance_sensor_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.min_distance , packet1.max_distance , packet1.current_distance , packet1.type , packet1.id , packet1.orientation , packet1.covariance ); - mavlink_msg_distance_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_distance_sensor_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.min_distance , packet1.max_distance , packet1.current_distance , packet1.type , packet1.id , packet1.orientation , packet1.covariance ); - mavlink_msg_distance_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_REQUEST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_request_t packet_in = { - 93372036854775807ULL,963497880,963498088,18067 - }; - mavlink_terrain_request_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.mask = packet_in.mask; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.grid_spacing = packet_in.grid_spacing; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_request_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_request_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask ); - mavlink_msg_terrain_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask ); - mavlink_msg_terrain_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_data_t packet_in = { - 963497464,963497672,17651,{ 17755, 17756, 17757, 17758, 17759, 17760, 17761, 17762, 17763, 17764, 17765, 17766, 17767, 17768, 17769, 17770 },3 - }; - mavlink_terrain_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.grid_spacing = packet_in.grid_spacing; - packet1.gridbit = packet_in.gridbit; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(int16_t)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_data_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data ); - mavlink_msg_terrain_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data ); - mavlink_msg_terrain_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_CHECK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_check_t packet_in = { - 963497464,963497672 - }; - mavlink_terrain_check_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_check_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_check_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_check_pack(system_id, component_id, &msg , packet1.lat , packet1.lon ); - mavlink_msg_terrain_check_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_check_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon ); - mavlink_msg_terrain_check_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_REPORT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_report_t packet_in = { - 963497464,963497672,73.0,101.0,18067,18171,18275 - }; - mavlink_terrain_report_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.terrain_height = packet_in.terrain_height; - packet1.current_height = packet_in.current_height; - packet1.spacing = packet_in.spacing; - packet1.pending = packet_in.pending; - packet1.loaded = packet_in.loaded; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_report_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_report_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.spacing , packet1.terrain_height , packet1.current_height , packet1.pending , packet1.loaded ); - mavlink_msg_terrain_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.spacing , packet1.terrain_height , packet1.current_height , packet1.pending , packet1.loaded ); - mavlink_msg_terrain_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_PRESSURE2 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_pressure2_t packet_in = { - 963497464,45.0,73.0,17859 - }; - mavlink_scaled_pressure2_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff = packet_in.press_diff; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure2_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_pressure2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure2_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATT_POS_MOCAP >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_att_pos_mocap_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0 },185.0,213.0,241.0 - }; - mavlink_att_pos_mocap_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_att_pos_mocap_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_att_pos_mocap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_att_pos_mocap_pack(system_id, component_id, &msg , packet1.time_usec , packet1.q , packet1.x , packet1.y , packet1.z ); - mavlink_msg_att_pos_mocap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.q , packet1.x , packet1.y , packet1.z ); - mavlink_msg_att_pos_mocap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_actuator_control_target_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0, 77.0, 78.0, 79.0, 80.0 },125,192,3 - }; - mavlink_set_actuator_control_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.group_mlx = packet_in.group_mlx; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.controls, packet_in.controls, sizeof(float)*8); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_actuator_control_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_actuator_control_target_pack(system_id, component_id, &msg , packet1.time_usec , packet1.group_mlx , packet1.target_system , packet1.target_component , packet1.controls ); - mavlink_msg_set_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_actuator_control_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.group_mlx , packet1.target_system , packet1.target_component , packet1.controls ); - mavlink_msg_set_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_actuator_control_target_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0, 77.0, 78.0, 79.0, 80.0 },125 - }; - mavlink_actuator_control_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.group_mlx = packet_in.group_mlx; - - mav_array_memcpy(packet1.controls, packet_in.controls, sizeof(float)*8); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_control_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_control_target_pack(system_id, component_id, &msg , packet1.time_usec , packet1.group_mlx , packet1.controls ); - mavlink_msg_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_control_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.group_mlx , packet1.controls ); - mavlink_msg_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ALTITUDE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_altitude_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0 - }; - mavlink_altitude_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.altitude_monotonic = packet_in.altitude_monotonic; - packet1.altitude_amsl = packet_in.altitude_amsl; - packet1.altitude_local = packet_in.altitude_local; - packet1.altitude_relative = packet_in.altitude_relative; - packet1.altitude_terrain = packet_in.altitude_terrain; - packet1.bottom_clearance = packet_in.bottom_clearance; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ALTITUDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ALTITUDE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_altitude_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_altitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_altitude_pack(system_id, component_id, &msg , packet1.time_usec , packet1.altitude_monotonic , packet1.altitude_amsl , packet1.altitude_local , packet1.altitude_relative , packet1.altitude_terrain , packet1.bottom_clearance ); - mavlink_msg_altitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_altitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.altitude_monotonic , packet1.altitude_amsl , packet1.altitude_local , packet1.altitude_relative , packet1.altitude_terrain , packet1.bottom_clearance ); - mavlink_msg_altitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RESOURCE_REQUEST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_resource_request_t packet_in = { - 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2 },243,{ 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173 } - }; - mavlink_resource_request_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.request_id = packet_in.request_id; - packet1.uri_type = packet_in.uri_type; - packet1.transfer_type = packet_in.transfer_type; - - mav_array_memcpy(packet1.uri, packet_in.uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet1.storage, packet_in.storage, sizeof(uint8_t)*120); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_resource_request_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_resource_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_resource_request_pack(system_id, component_id, &msg , packet1.request_id , packet1.uri_type , packet1.uri , packet1.transfer_type , packet1.storage ); - mavlink_msg_resource_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_resource_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.request_id , packet1.uri_type , packet1.uri , packet1.transfer_type , packet1.storage ); - mavlink_msg_resource_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_PRESSURE3 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_pressure3_t packet_in = { - 963497464,45.0,73.0,17859 - }; - mavlink_scaled_pressure3_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff = packet_in.press_diff; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure3_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_pressure3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure3_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure3_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature ); - mavlink_msg_scaled_pressure3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FOLLOW_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_follow_target_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,963498296,963498504,185.0,{ 213.0, 214.0, 215.0 },{ 297.0, 298.0, 299.0 },{ 381.0, 382.0, 383.0, 384.0 },{ 493.0, 494.0, 495.0 },{ 577.0, 578.0, 579.0 },25 - }; - mavlink_follow_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.timestamp = packet_in.timestamp; - packet1.custom_state = packet_in.custom_state; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.est_capabilities = packet_in.est_capabilities; - - mav_array_memcpy(packet1.vel, packet_in.vel, sizeof(float)*3); - mav_array_memcpy(packet1.acc, packet_in.acc, sizeof(float)*3); - mav_array_memcpy(packet1.attitude_q, packet_in.attitude_q, sizeof(float)*4); - mav_array_memcpy(packet1.rates, packet_in.rates, sizeof(float)*3); - mav_array_memcpy(packet1.position_cov, packet_in.position_cov, sizeof(float)*3); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_follow_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_follow_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_follow_target_pack(system_id, component_id, &msg , packet1.timestamp , packet1.est_capabilities , packet1.lat , packet1.lon , packet1.alt , packet1.vel , packet1.acc , packet1.attitude_q , packet1.rates , packet1.position_cov , packet1.custom_state ); - mavlink_msg_follow_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_follow_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.est_capabilities , packet1.lat , packet1.lon , packet1.alt , packet1.vel , packet1.acc , packet1.attitude_q , packet1.rates , packet1.position_cov , packet1.custom_state ); - mavlink_msg_follow_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_control_system_state_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,{ 353.0, 354.0, 355.0 },{ 437.0, 438.0, 439.0 },{ 521.0, 522.0, 523.0, 524.0 },633.0,661.0,689.0 - }; - mavlink_control_system_state_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x_acc = packet_in.x_acc; - packet1.y_acc = packet_in.y_acc; - packet1.z_acc = packet_in.z_acc; - packet1.x_vel = packet_in.x_vel; - packet1.y_vel = packet_in.y_vel; - packet1.z_vel = packet_in.z_vel; - packet1.x_pos = packet_in.x_pos; - packet1.y_pos = packet_in.y_pos; - packet1.z_pos = packet_in.z_pos; - packet1.airspeed = packet_in.airspeed; - packet1.roll_rate = packet_in.roll_rate; - packet1.pitch_rate = packet_in.pitch_rate; - packet1.yaw_rate = packet_in.yaw_rate; - - mav_array_memcpy(packet1.vel_variance, packet_in.vel_variance, sizeof(float)*3); - mav_array_memcpy(packet1.pos_variance, packet_in.pos_variance, sizeof(float)*3); - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_control_system_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_control_system_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_control_system_state_pack(system_id, component_id, &msg , packet1.time_usec , packet1.x_acc , packet1.y_acc , packet1.z_acc , packet1.x_vel , packet1.y_vel , packet1.z_vel , packet1.x_pos , packet1.y_pos , packet1.z_pos , packet1.airspeed , packet1.vel_variance , packet1.pos_variance , packet1.q , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate ); - mavlink_msg_control_system_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_control_system_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.x_acc , packet1.y_acc , packet1.z_acc , packet1.x_vel , packet1.y_vel , packet1.z_vel , packet1.x_pos , packet1.y_pos , packet1.z_pos , packet1.airspeed , packet1.vel_variance , packet1.pos_variance , packet1.q , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate ); - mavlink_msg_control_system_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_BATTERY_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_battery_status_t packet_in = { - 963497464,963497672,17651,{ 17755, 17756, 17757, 17758, 17759, 17760, 17761, 17762, 17763, 17764 },18795,101,168,235,46 - }; - mavlink_battery_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.current_consumed = packet_in.current_consumed; - packet1.energy_consumed = packet_in.energy_consumed; - packet1.temperature = packet_in.temperature; - packet1.current_battery = packet_in.current_battery; - packet1.id = packet_in.id; - packet1.battery_function = packet_in.battery_function; - packet1.type = packet_in.type; - packet1.battery_remaining = packet_in.battery_remaining; - - mav_array_memcpy(packet1.voltages, packet_in.voltages, sizeof(uint16_t)*10); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_battery_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_battery_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_battery_status_pack(system_id, component_id, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining ); - mavlink_msg_battery_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_battery_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining ); - mavlink_msg_battery_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AUTOPILOT_VERSION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_autopilot_version_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,963498296,963498504,963498712,963498920,18899,19003,{ 113, 114, 115, 116, 117, 118, 119, 120 },{ 137, 138, 139, 140, 141, 142, 143, 144 },{ 161, 162, 163, 164, 165, 166, 167, 168 } - }; - mavlink_autopilot_version_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.capabilities = packet_in.capabilities; - packet1.uid = packet_in.uid; - packet1.flight_sw_version = packet_in.flight_sw_version; - packet1.middleware_sw_version = packet_in.middleware_sw_version; - packet1.os_sw_version = packet_in.os_sw_version; - packet1.board_version = packet_in.board_version; - packet1.vendor_id = packet_in.vendor_id; - packet1.product_id = packet_in.product_id; - - mav_array_memcpy(packet1.flight_custom_version, packet_in.flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet1.middleware_custom_version, packet_in.middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet1.os_custom_version, packet_in.os_custom_version, sizeof(uint8_t)*8); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_version_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_autopilot_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_version_pack(system_id, component_id, &msg , packet1.capabilities , packet1.flight_sw_version , packet1.middleware_sw_version , packet1.os_sw_version , packet1.board_version , packet1.flight_custom_version , packet1.middleware_custom_version , packet1.os_custom_version , packet1.vendor_id , packet1.product_id , packet1.uid ); - mavlink_msg_autopilot_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_version_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.capabilities , packet1.flight_sw_version , packet1.middleware_sw_version , packet1.os_sw_version , packet1.board_version , packet1.flight_custom_version , packet1.middleware_custom_version , packet1.os_custom_version , packet1.vendor_id , packet1.product_id , packet1.uid ); - mavlink_msg_autopilot_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LANDING_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_landing_target_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,89,156 - }; - mavlink_landing_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.angle_x = packet_in.angle_x; - packet1.angle_y = packet_in.angle_y; - packet1.distance = packet_in.distance; - packet1.size_x = packet_in.size_x; - packet1.size_y = packet_in.size_y; - packet1.target_num = packet_in.target_num; - packet1.frame = packet_in.frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_landing_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_landing_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_landing_target_pack(system_id, component_id, &msg , packet1.time_usec , packet1.target_num , packet1.frame , packet1.angle_x , packet1.angle_y , packet1.distance , packet1.size_x , packet1.size_y ); - mavlink_msg_landing_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_landing_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.target_num , packet1.frame , packet1.angle_x , packet1.angle_y , packet1.distance , packet1.size_x , packet1.size_y ); - mavlink_msg_landing_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESTIMATOR_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_estimator_status_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,19315 - }; - mavlink_estimator_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.vel_ratio = packet_in.vel_ratio; - packet1.pos_horiz_ratio = packet_in.pos_horiz_ratio; - packet1.pos_vert_ratio = packet_in.pos_vert_ratio; - packet1.mag_ratio = packet_in.mag_ratio; - packet1.hagl_ratio = packet_in.hagl_ratio; - packet1.tas_ratio = packet_in.tas_ratio; - packet1.pos_horiz_accuracy = packet_in.pos_horiz_accuracy; - packet1.pos_vert_accuracy = packet_in.pos_vert_accuracy; - packet1.flags = packet_in.flags; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_estimator_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_estimator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_estimator_status_pack(system_id, component_id, &msg , packet1.time_usec , packet1.flags , packet1.vel_ratio , packet1.pos_horiz_ratio , packet1.pos_vert_ratio , packet1.mag_ratio , packet1.hagl_ratio , packet1.tas_ratio , packet1.pos_horiz_accuracy , packet1.pos_vert_accuracy ); - mavlink_msg_estimator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_estimator_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.flags , packet1.vel_ratio , packet1.pos_horiz_ratio , packet1.pos_vert_ratio , packet1.mag_ratio , packet1.hagl_ratio , packet1.tas_ratio , packet1.pos_horiz_accuracy , packet1.pos_vert_accuracy ); - mavlink_msg_estimator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_WIND_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_wind_cov_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0 - }; - mavlink_wind_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.wind_x = packet_in.wind_x; - packet1.wind_y = packet_in.wind_y; - packet1.wind_z = packet_in.wind_z; - packet1.var_horiz = packet_in.var_horiz; - packet1.var_vert = packet_in.var_vert; - packet1.wind_alt = packet_in.wind_alt; - packet1.horiz_accuracy = packet_in.horiz_accuracy; - packet1.vert_accuracy = packet_in.vert_accuracy; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_WIND_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WIND_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wind_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_wind_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wind_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.wind_x , packet1.wind_y , packet1.wind_z , packet1.var_horiz , packet1.var_vert , packet1.wind_alt , packet1.horiz_accuracy , packet1.vert_accuracy ); - mavlink_msg_wind_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wind_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.wind_x , packet1.wind_y , packet1.wind_z , packet1.var_horiz , packet1.var_vert , packet1.wind_alt , packet1.horiz_accuracy , packet1.vert_accuracy ); - mavlink_msg_wind_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_INPUT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_input_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,20147,20251,185,252,63 - }; - mavlink_gps_input_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.time_week_ms = packet_in.time_week_ms; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.hdop = packet_in.hdop; - packet1.vdop = packet_in.vdop; - packet1.vn = packet_in.vn; - packet1.ve = packet_in.ve; - packet1.vd = packet_in.vd; - packet1.speed_accuracy = packet_in.speed_accuracy; - packet1.horiz_accuracy = packet_in.horiz_accuracy; - packet1.vert_accuracy = packet_in.vert_accuracy; - packet1.ignore_flags = packet_in.ignore_flags; - packet1.time_week = packet_in.time_week; - packet1.gps_id = packet_in.gps_id; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_input_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_input_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_input_pack(system_id, component_id, &msg , packet1.time_usec , packet1.gps_id , packet1.ignore_flags , packet1.time_week_ms , packet1.time_week , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.hdop , packet1.vdop , packet1.vn , packet1.ve , packet1.vd , packet1.speed_accuracy , packet1.horiz_accuracy , packet1.vert_accuracy , packet1.satellites_visible ); - mavlink_msg_gps_input_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_input_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.gps_id , packet1.ignore_flags , packet1.time_week_ms , packet1.time_week , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.hdop , packet1.vdop , packet1.vn , packet1.ve , packet1.vd , packet1.speed_accuracy , packet1.horiz_accuracy , packet1.vert_accuracy , packet1.satellites_visible ); - mavlink_msg_gps_input_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_RTCM_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_rtcm_data_t packet_in = { - 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62 } - }; - mavlink_gps_rtcm_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.flags = packet_in.flags; - packet1.len = packet_in.len; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*180); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtcm_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_rtcm_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtcm_data_pack(system_id, component_id, &msg , packet1.flags , packet1.len , packet1.data ); - mavlink_msg_gps_rtcm_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtcm_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.flags , packet1.len , packet1.data ); - mavlink_msg_gps_rtcm_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIGH_LATENCY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_high_latency_t packet_in = { - 963497464,963497672,963497880,17859,17963,18067,18171,18275,18379,18483,211,22,89,156,223,34,101,168,235,46,113,180,247,58 - }; - mavlink_high_latency_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.custom_mode = packet_in.custom_mode; - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.heading = packet_in.heading; - packet1.heading_sp = packet_in.heading_sp; - packet1.altitude_amsl = packet_in.altitude_amsl; - packet1.altitude_sp = packet_in.altitude_sp; - packet1.wp_distance = packet_in.wp_distance; - packet1.base_mode = packet_in.base_mode; - packet1.landed_state = packet_in.landed_state; - packet1.throttle = packet_in.throttle; - packet1.airspeed = packet_in.airspeed; - packet1.airspeed_sp = packet_in.airspeed_sp; - packet1.groundspeed = packet_in.groundspeed; - packet1.climb_rate = packet_in.climb_rate; - packet1.gps_nsat = packet_in.gps_nsat; - packet1.gps_fix_type = packet_in.gps_fix_type; - packet1.battery_remaining = packet_in.battery_remaining; - packet1.temperature = packet_in.temperature; - packet1.temperature_air = packet_in.temperature_air; - packet1.failsafe = packet_in.failsafe; - packet1.wp_num = packet_in.wp_num; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_high_latency_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency_pack(system_id, component_id, &msg , packet1.base_mode , packet1.custom_mode , packet1.landed_state , packet1.roll , packet1.pitch , packet1.heading , packet1.throttle , packet1.heading_sp , packet1.latitude , packet1.longitude , packet1.altitude_amsl , packet1.altitude_sp , packet1.airspeed , packet1.airspeed_sp , packet1.groundspeed , packet1.climb_rate , packet1.gps_nsat , packet1.gps_fix_type , packet1.battery_remaining , packet1.temperature , packet1.temperature_air , packet1.failsafe , packet1.wp_num , packet1.wp_distance ); - mavlink_msg_high_latency_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.base_mode , packet1.custom_mode , packet1.landed_state , packet1.roll , packet1.pitch , packet1.heading , packet1.throttle , packet1.heading_sp , packet1.latitude , packet1.longitude , packet1.altitude_amsl , packet1.altitude_sp , packet1.airspeed , packet1.airspeed_sp , packet1.groundspeed , packet1.climb_rate , packet1.gps_nsat , packet1.gps_fix_type , packet1.battery_remaining , packet1.temperature , packet1.temperature_air , packet1.failsafe , packet1.wp_num , packet1.wp_distance ); - mavlink_msg_high_latency_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VIBRATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vibration_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,963498504,963498712,963498920 - }; - mavlink_vibration_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.vibration_x = packet_in.vibration_x; - packet1.vibration_y = packet_in.vibration_y; - packet1.vibration_z = packet_in.vibration_z; - packet1.clipping_0 = packet_in.clipping_0; - packet1.clipping_1 = packet_in.clipping_1; - packet1.clipping_2 = packet_in.clipping_2; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VIBRATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VIBRATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vibration_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vibration_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vibration_pack(system_id, component_id, &msg , packet1.time_usec , packet1.vibration_x , packet1.vibration_y , packet1.vibration_z , packet1.clipping_0 , packet1.clipping_1 , packet1.clipping_2 ); - mavlink_msg_vibration_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vibration_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.vibration_x , packet1.vibration_y , packet1.vibration_z , packet1.clipping_0 , packet1.clipping_1 , packet1.clipping_2 ); - mavlink_msg_vibration_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HOME_POSITION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_home_position_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,{ 185.0, 186.0, 187.0, 188.0 },297.0,325.0,353.0 - }; - mavlink_home_position_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.approach_x = packet_in.approach_x; - packet1.approach_y = packet_in.approach_y; - packet1.approach_z = packet_in.approach_z; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_home_position_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_home_position_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z ); - mavlink_msg_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_home_position_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z ); - mavlink_msg_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_HOME_POSITION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_home_position_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,{ 185.0, 186.0, 187.0, 188.0 },297.0,325.0,353.0,161 - }; - mavlink_set_home_position_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.approach_x = packet_in.approach_x; - packet1.approach_y = packet_in.approach_y; - packet1.approach_z = packet_in.approach_z; - packet1.target_system = packet_in.target_system; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_home_position_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_home_position_pack(system_id, component_id, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z ); - mavlink_msg_set_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_home_position_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z ); - mavlink_msg_set_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MESSAGE_INTERVAL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_message_interval_t packet_in = { - 963497464,17443 - }; - mavlink_message_interval_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.interval_us = packet_in.interval_us; - packet1.message_id = packet_in.message_id; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_message_interval_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_message_interval_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_message_interval_pack(system_id, component_id, &msg , packet1.message_id , packet1.interval_us ); - mavlink_msg_message_interval_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_message_interval_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.message_id , packet1.interval_us ); - mavlink_msg_message_interval_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_EXTENDED_SYS_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_extended_sys_state_t packet_in = { - 5,72 - }; - mavlink_extended_sys_state_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.vtol_state = packet_in.vtol_state; - packet1.landed_state = packet_in.landed_state; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_extended_sys_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_extended_sys_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_extended_sys_state_pack(system_id, component_id, &msg , packet1.vtol_state , packet1.landed_state ); - mavlink_msg_extended_sys_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_extended_sys_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.vtol_state , packet1.landed_state ); - mavlink_msg_extended_sys_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ADSB_VEHICLE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_adsb_vehicle_t packet_in = { - 963497464,963497672,963497880,963498088,18067,18171,18275,18379,18483,211,"BCDEFGHI",113,180 - }; - mavlink_adsb_vehicle_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.ICAO_address = packet_in.ICAO_address; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.altitude = packet_in.altitude; - packet1.heading = packet_in.heading; - packet1.hor_velocity = packet_in.hor_velocity; - packet1.ver_velocity = packet_in.ver_velocity; - packet1.flags = packet_in.flags; - packet1.squawk = packet_in.squawk; - packet1.altitude_type = packet_in.altitude_type; - packet1.emitter_type = packet_in.emitter_type; - packet1.tslc = packet_in.tslc; - - mav_array_memcpy(packet1.callsign, packet_in.callsign, sizeof(char)*9); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_adsb_vehicle_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_adsb_vehicle_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_adsb_vehicle_pack(system_id, component_id, &msg , packet1.ICAO_address , packet1.lat , packet1.lon , packet1.altitude_type , packet1.altitude , packet1.heading , packet1.hor_velocity , packet1.ver_velocity , packet1.callsign , packet1.emitter_type , packet1.tslc , packet1.flags , packet1.squawk ); - mavlink_msg_adsb_vehicle_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_adsb_vehicle_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ICAO_address , packet1.lat , packet1.lon , packet1.altitude_type , packet1.altitude , packet1.heading , packet1.hor_velocity , packet1.ver_velocity , packet1.callsign , packet1.emitter_type , packet1.tslc , packet1.flags , packet1.squawk ); - mavlink_msg_adsb_vehicle_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COLLISION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_collision_t packet_in = { - 963497464,45.0,73.0,101.0,53,120,187 - }; - mavlink_collision_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.id = packet_in.id; - packet1.time_to_minimum_delta = packet_in.time_to_minimum_delta; - packet1.altitude_minimum_delta = packet_in.altitude_minimum_delta; - packet1.horizontal_minimum_delta = packet_in.horizontal_minimum_delta; - packet1.src = packet_in.src; - packet1.action = packet_in.action; - packet1.threat_level = packet_in.threat_level; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COLLISION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COLLISION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_collision_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_collision_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_collision_pack(system_id, component_id, &msg , packet1.src , packet1.id , packet1.action , packet1.threat_level , packet1.time_to_minimum_delta , packet1.altitude_minimum_delta , packet1.horizontal_minimum_delta ); - mavlink_msg_collision_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_collision_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.src , packet1.id , packet1.action , packet1.threat_level , packet1.time_to_minimum_delta , packet1.altitude_minimum_delta , packet1.horizontal_minimum_delta ); - mavlink_msg_collision_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_V2_EXTENSION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_v2_extension_t packet_in = { - 17235,139,206,17,{ 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76 } - }; - mavlink_v2_extension_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.message_type = packet_in.message_type; - packet1.target_network = packet_in.target_network; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.payload, packet_in.payload, sizeof(uint8_t)*249); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_v2_extension_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_v2_extension_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_v2_extension_pack(system_id, component_id, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.message_type , packet1.payload ); - mavlink_msg_v2_extension_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_v2_extension_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.message_type , packet1.payload ); - mavlink_msg_v2_extension_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MEMORY_VECT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_memory_vect_t packet_in = { - 17235,139,206,{ 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48 } - }; - mavlink_memory_vect_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.address = packet_in.address; - packet1.ver = packet_in.ver; - packet1.type = packet_in.type; - - mav_array_memcpy(packet1.value, packet_in.value, sizeof(int8_t)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_memory_vect_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_memory_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_memory_vect_pack(system_id, component_id, &msg , packet1.address , packet1.ver , packet1.type , packet1.value ); - mavlink_msg_memory_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_memory_vect_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.address , packet1.ver , packet1.type , packet1.value ); - mavlink_msg_memory_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEBUG_VECT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_debug_vect_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,"UVWXYZABC" - }; - mavlink_debug_vect_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_vect_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_debug_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_vect_pack(system_id, component_id, &msg , packet1.name , packet1.time_usec , packet1.x , packet1.y , packet1.z ); - mavlink_msg_debug_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_vect_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.name , packet1.time_usec , packet1.x , packet1.y , packet1.z ); - mavlink_msg_debug_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_NAMED_VALUE_FLOAT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_named_value_float_t packet_in = { - 963497464,45.0,"IJKLMNOPQ" - }; - mavlink_named_value_float_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.value = packet_in.value; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_float_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_named_value_float_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_float_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_float_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_float_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_float_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_NAMED_VALUE_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_named_value_int_t packet_in = { - 963497464,963497672,"IJKLMNOPQ" - }; - mavlink_named_value_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.value = packet_in.value; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_named_value_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_STATUSTEXT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_statustext_t packet_in = { - 5,"BCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWX" - }; - mavlink_statustext_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.severity = packet_in.severity; - - mav_array_memcpy(packet1.text, packet_in.text, sizeof(char)*50); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_statustext_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_statustext_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_statustext_pack(system_id, component_id, &msg , packet1.severity , packet1.text ); - mavlink_msg_statustext_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_statustext_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.severity , packet1.text ); - mavlink_msg_statustext_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEBUG >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_debug_t packet_in = { - 963497464,45.0,29 - }; - mavlink_debug_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.value = packet_in.value; - packet1.ind = packet_in.ind; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DEBUG_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEBUG_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_debug_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.ind , packet1.value ); - mavlink_msg_debug_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.ind , packet1.value ); - mavlink_msg_debug_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SETUP_SIGNING >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_setup_signing_t packet_in = { - 93372036854775807ULL,29,96,{ 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194 } - }; - mavlink_setup_signing_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.initial_timestamp = packet_in.initial_timestamp; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.secret_key, packet_in.secret_key, sizeof(uint8_t)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_setup_signing_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_setup_signing_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_setup_signing_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.secret_key , packet1.initial_timestamp ); - mavlink_msg_setup_signing_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_setup_signing_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.secret_key , packet1.initial_timestamp ); - mavlink_msg_setup_signing_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_BUTTON_CHANGE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_button_change_t packet_in = { - 963497464,963497672,29 - }; - mavlink_button_change_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.last_change_ms = packet_in.last_change_ms; - packet1.state = packet_in.state; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_button_change_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_button_change_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_button_change_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.last_change_ms , packet1.state ); - mavlink_msg_button_change_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_button_change_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.last_change_ms , packet1.state ); - mavlink_msg_button_change_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PLAY_TUNE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_play_tune_t packet_in = { - 5,72,"CDEFGHIJKLMNOPQRSTUVWXYZABCDE" - }; - mavlink_play_tune_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.tune, packet_in.tune, sizeof(char)*30); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_play_tune_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_play_tune_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_play_tune_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.tune ); - mavlink_msg_play_tune_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_play_tune_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.tune ); - mavlink_msg_play_tune_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_INFORMATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_information_t packet_in = { - 963497464,45.0,73.0,101.0,18067,18171,65,{ 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163 },{ 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3 },68 - }; - mavlink_camera_information_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.focal_length = packet_in.focal_length; - packet1.sensor_size_h = packet_in.sensor_size_h; - packet1.sensor_size_v = packet_in.sensor_size_v; - packet1.resolution_h = packet_in.resolution_h; - packet1.resolution_v = packet_in.resolution_v; - packet1.camera_id = packet_in.camera_id; - packet1.lense_id = packet_in.lense_id; - - mav_array_memcpy(packet1.vendor_name, packet_in.vendor_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet1.model_name, packet_in.model_name, sizeof(uint8_t)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_information_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_information_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.camera_id , packet1.vendor_name , packet1.model_name , packet1.focal_length , packet1.sensor_size_h , packet1.sensor_size_v , packet1.resolution_h , packet1.resolution_v , packet1.lense_id ); - mavlink_msg_camera_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.camera_id , packet1.vendor_name , packet1.model_name , packet1.focal_length , packet1.sensor_size_h , packet1.sensor_size_v , packet1.resolution_h , packet1.resolution_v , packet1.lense_id ); - mavlink_msg_camera_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_SETTINGS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_settings_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,65,132,199,10,77,144,211,22 - }; - mavlink_camera_settings_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.aperture = packet_in.aperture; - packet1.shutter_speed = packet_in.shutter_speed; - packet1.iso_sensitivity = packet_in.iso_sensitivity; - packet1.white_balance = packet_in.white_balance; - packet1.camera_id = packet_in.camera_id; - packet1.aperture_locked = packet_in.aperture_locked; - packet1.shutter_speed_locked = packet_in.shutter_speed_locked; - packet1.iso_sensitivity_locked = packet_in.iso_sensitivity_locked; - packet1.white_balance_locked = packet_in.white_balance_locked; - packet1.mode_id = packet_in.mode_id; - packet1.color_mode_id = packet_in.color_mode_id; - packet1.image_format_id = packet_in.image_format_id; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_settings_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_settings_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_settings_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.camera_id , packet1.aperture , packet1.aperture_locked , packet1.shutter_speed , packet1.shutter_speed_locked , packet1.iso_sensitivity , packet1.iso_sensitivity_locked , packet1.white_balance , packet1.white_balance_locked , packet1.mode_id , packet1.color_mode_id , packet1.image_format_id ); - mavlink_msg_camera_settings_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_settings_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.camera_id , packet1.aperture , packet1.aperture_locked , packet1.shutter_speed , packet1.shutter_speed_locked , packet1.iso_sensitivity , packet1.iso_sensitivity_locked , packet1.white_balance , packet1.white_balance_locked , packet1.mode_id , packet1.color_mode_id , packet1.image_format_id ); - mavlink_msg_camera_settings_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_STORAGE_INFORMATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_storage_information_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,77,144 - }; - mavlink_storage_information_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.total_capacity = packet_in.total_capacity; - packet1.used_capacity = packet_in.used_capacity; - packet1.available_capacity = packet_in.available_capacity; - packet1.read_speed = packet_in.read_speed; - packet1.write_speed = packet_in.write_speed; - packet1.storage_id = packet_in.storage_id; - packet1.status = packet_in.status; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_storage_information_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_storage_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_storage_information_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.storage_id , packet1.status , packet1.total_capacity , packet1.used_capacity , packet1.available_capacity , packet1.read_speed , packet1.write_speed ); - mavlink_msg_storage_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_storage_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.storage_id , packet1.status , packet1.total_capacity , packet1.used_capacity , packet1.available_capacity , packet1.read_speed , packet1.write_speed ); - mavlink_msg_storage_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_capture_status_t packet_in = { - 963497464,45.0,73.0,963498088,129.0,18275,18379,18483,18587,89,156,223 - }; - mavlink_camera_capture_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.image_interval = packet_in.image_interval; - packet1.video_framerate = packet_in.video_framerate; - packet1.recording_time_ms = packet_in.recording_time_ms; - packet1.available_capacity = packet_in.available_capacity; - packet1.image_resolution_h = packet_in.image_resolution_h; - packet1.image_resolution_v = packet_in.image_resolution_v; - packet1.video_resolution_h = packet_in.video_resolution_h; - packet1.video_resolution_v = packet_in.video_resolution_v; - packet1.camera_id = packet_in.camera_id; - packet1.image_status = packet_in.image_status; - packet1.video_status = packet_in.video_status; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_capture_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_capture_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_capture_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.camera_id , packet1.image_status , packet1.video_status , packet1.image_interval , packet1.video_framerate , packet1.image_resolution_h , packet1.image_resolution_v , packet1.video_resolution_h , packet1.video_resolution_v , packet1.recording_time_ms , packet1.available_capacity ); - mavlink_msg_camera_capture_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_capture_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.camera_id , packet1.image_status , packet1.video_status , packet1.image_interval , packet1.video_framerate , packet1.image_resolution_h , packet1.image_resolution_v , packet1.video_resolution_h , packet1.video_resolution_v , packet1.recording_time_ms , packet1.available_capacity ); - mavlink_msg_camera_capture_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_image_captured_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,963498504,963498712,{ 213.0, 214.0, 215.0, 216.0 },963499752,149,216,"YZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRST" - }; - mavlink_camera_image_captured_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_utc = packet_in.time_utc; - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.relative_alt = packet_in.relative_alt; - packet1.image_index = packet_in.image_index; - packet1.camera_id = packet_in.camera_id; - packet1.capture_result = packet_in.capture_result; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - mav_array_memcpy(packet1.file_url, packet_in.file_url, sizeof(char)*205); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_image_captured_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_image_captured_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_image_captured_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.time_utc , packet1.camera_id , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.q , packet1.image_index , packet1.capture_result , packet1.file_url ); - mavlink_msg_camera_image_captured_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_image_captured_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.time_utc , packet1.camera_id , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.q , packet1.image_index , packet1.capture_result , packet1.file_url ); - mavlink_msg_camera_image_captured_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FLIGHT_INFORMATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_flight_information_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,963498712 - }; - mavlink_flight_information_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.arming_time_utc = packet_in.arming_time_utc; - packet1.takeoff_time_utc = packet_in.takeoff_time_utc; - packet1.flight_uuid = packet_in.flight_uuid; - packet1.time_boot_ms = packet_in.time_boot_ms; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_flight_information_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_flight_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_flight_information_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.arming_time_utc , packet1.takeoff_time_utc , packet1.flight_uuid ); - mavlink_msg_flight_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_flight_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.arming_time_utc , packet1.takeoff_time_utc , packet1.flight_uuid ); - mavlink_msg_flight_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MOUNT_ORIENTATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mount_orientation_t packet_in = { - 963497464,45.0,73.0,101.0 - }; - mavlink_mount_orientation_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mount_orientation_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mount_orientation_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mount_orientation_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_mount_orientation_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mount_orientation_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_mount_orientation_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOGGING_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_logging_data_t packet_in = { - 17235,139,206,17,84,{ 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143 } - }; - mavlink_logging_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.sequence = packet_in.sequence; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.length = packet_in.length; - packet1.first_message_offset = packet_in.first_message_offset; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*249); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_logging_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.length , packet1.first_message_offset , packet1.data ); - mavlink_msg_logging_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.length , packet1.first_message_offset , packet1.data ); - mavlink_msg_logging_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOGGING_DATA_ACKED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_logging_data_acked_t packet_in = { - 17235,139,206,17,84,{ 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143 } - }; - mavlink_logging_data_acked_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.sequence = packet_in.sequence; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.length = packet_in.length; - packet1.first_message_offset = packet_in.first_message_offset; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*249); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_acked_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_logging_data_acked_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_acked_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.length , packet1.first_message_offset , packet1.data ); - mavlink_msg_logging_data_acked_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_acked_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.length , packet1.first_message_offset , packet1.data ); - mavlink_msg_logging_data_acked_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOGGING_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_logging_ack_t packet_in = { - 17235,139,206 - }; - mavlink_logging_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.sequence = packet_in.sequence; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_logging_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_ack_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.sequence ); - mavlink_msg_logging_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.sequence ); - mavlink_msg_logging_ack_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 - -#ifndef M_PI_2 - #define M_PI_2 ((float)asin(1)) -#endif - -/** - * @file mavlink_conversions.h - * - * These conversion functions follow the NASA rotation standards definition file - * available online. - * - * Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free - * (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free) - * rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the - * protocol as widely as possible. - * - * @author James Goppert - * @author Thomas Gubler - */ - - -/** - * Converts a quaternion to a rotation matrix - * - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - * @param dcm a 3x3 rotation matrix - */ -MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3]) -{ - double a = quaternion[0]; - double b = quaternion[1]; - double c = quaternion[2]; - double d = quaternion[3]; - double aSq = a * a; - double bSq = b * b; - double cSq = c * c; - double dSq = d * d; - dcm[0][0] = aSq + bSq - cSq - dSq; - dcm[0][1] = 2 * (b * c - a * d); - dcm[0][2] = 2 * (a * c + b * d); - dcm[1][0] = 2 * (b * c + a * d); - dcm[1][1] = aSq - bSq + cSq - dSq; - dcm[1][2] = 2 * (c * d - a * b); - dcm[2][0] = 2 * (b * d - a * c); - dcm[2][1] = 2 * (a * b + c * d); - dcm[2][2] = aSq - bSq - cSq + dSq; -} - - -/** - * Converts a rotation matrix to euler angles - * - * @param dcm a 3x3 rotation matrix - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - */ -MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw) -{ - float phi, theta, psi; - theta = asin(-dcm[2][0]); - - if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) { - phi = 0.0f; - psi = (atan2f(dcm[1][2] - dcm[0][1], - dcm[0][2] + dcm[1][1]) + phi); - - } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) { - phi = 0.0f; - psi = atan2f(dcm[1][2] - dcm[0][1], - dcm[0][2] + dcm[1][1] - phi); - - } else { - phi = atan2f(dcm[2][1], dcm[2][2]); - psi = atan2f(dcm[1][0], dcm[0][0]); - } - - *roll = phi; - *pitch = theta; - *yaw = psi; -} - - -/** - * Converts a quaternion to euler angles - * - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - */ -MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw) -{ - float dcm[3][3]; - mavlink_quaternion_to_dcm(quaternion, dcm); - mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw); -} - - -/** - * Converts euler angles to a quaternion - * - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - */ -MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4]) -{ - float cosPhi_2 = cosf(roll / 2); - float sinPhi_2 = sinf(roll / 2); - float cosTheta_2 = cosf(pitch / 2); - float sinTheta_2 = sinf(pitch / 2); - float cosPsi_2 = cosf(yaw / 2); - float sinPsi_2 = sinf(yaw / 2); - quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 + - sinPhi_2 * sinTheta_2 * sinPsi_2); - quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 - - cosPhi_2 * sinTheta_2 * sinPsi_2); - quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 + - sinPhi_2 * cosTheta_2 * sinPsi_2); - quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 - - sinPhi_2 * sinTheta_2 * cosPsi_2); -} - - -/** - * Converts a rotation matrix to a quaternion - * Reference: - * - Shoemake, Quaternions, - * http://www.cs.ucr.edu/~vbz/resources/quatut.pdf - * - * @param dcm a 3x3 rotation matrix - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - */ -MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4]) -{ - float tr = dcm[0][0] + dcm[1][1] + dcm[2][2]; - if (tr > 0.0f) { - float s = sqrtf(tr + 1.0f); - quaternion[0] = s * 0.5f; - s = 0.5f / s; - quaternion[1] = (dcm[2][1] - dcm[1][2]) * s; - quaternion[2] = (dcm[0][2] - dcm[2][0]) * s; - quaternion[3] = (dcm[1][0] - dcm[0][1]) * s; - } else { - /* Find maximum diagonal element in dcm - * store index in dcm_i */ - int dcm_i = 0; - int i; - for (i = 1; i < 3; i++) { - if (dcm[i][i] > dcm[dcm_i][dcm_i]) { - dcm_i = i; - } - } - - int dcm_j = (dcm_i + 1) % 3; - int dcm_k = (dcm_i + 2) % 3; - - float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] - - dcm[dcm_k][dcm_k]) + 1.0f); - quaternion[dcm_i + 1] = s * 0.5f; - s = 0.5f / s; - quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s; - quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s; - quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s; - } -} - - -/** - * Converts euler angles to a rotation matrix - * - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - * @param dcm a 3x3 rotation matrix - */ -MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3]) -{ - float cosPhi = cosf(roll); - float sinPhi = sinf(roll); - float cosThe = cosf(pitch); - float sinThe = sinf(pitch); - float cosPsi = cosf(yaw); - float sinPsi = sinf(yaw); - - dcm[0][0] = cosThe * cosPsi; - dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi; - dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi; - - dcm[1][0] = cosThe * sinPsi; - dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi; - dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi; - - dcm[2][0] = -sinThe; - dcm[2][1] = sinPhi * cosThe; - dcm[2][2] = cosPhi * cosThe; -} - diff --git a/include/mavlink/v2.0/mavlink_get_info.h b/include/mavlink/v2.0/mavlink_get_info.h deleted file mode 100644 index b07e130..0000000 --- a/include/mavlink/v2.0/mavlink_get_info.h +++ /dev/null @@ -1,37 +0,0 @@ -#pragma once - -#ifdef MAVLINK_USE_MESSAGE_INFO -#define MAVLINK_HAVE_GET_MESSAGE_INFO -/* - return the message_info struct for a message -*/ -MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info(const mavlink_message_t *msg) -{ - static const mavlink_message_info_t mavlink_message_info[] = MAVLINK_MESSAGE_INFO; - /* - use a bisection search to find the right entry. A perfect hash may be better - Note that this assumes the table is sorted with primary key msgid - */ - uint32_t msgid = msg->msgid; - uint32_t low=0, high=sizeof(mavlink_message_info)/sizeof(mavlink_message_info[0]); - while (low < high) { - uint32_t mid = (low+1+high)/2; - if (msgid < mavlink_message_info[mid].msgid) { - high = mid-1; - continue; - } - if (msgid > mavlink_message_info[mid].msgid) { - low = mid; - continue; - } - low = mid; - break; - } - if (mavlink_message_info[low].msgid == msgid) { - return &mavlink_message_info[low]; - } - return NULL; -} -#endif // MAVLINK_USE_MESSAGE_INFO - - diff --git a/include/mavlink/v2.0/mavlink_helpers.h b/include/mavlink/v2.0/mavlink_helpers.h deleted file mode 100644 index 92a4fdc..0000000 --- a/include/mavlink/v2.0/mavlink_helpers.h +++ /dev/null @@ -1,1119 +0,0 @@ -#pragma once - -#include "string.h" -#include "checksum.h" -#include "mavlink_types.h" -#include "mavlink_conversions.h" -#include - -#ifndef MAVLINK_HELPER -#define MAVLINK_HELPER -#endif - -#include "mavlink_sha256.h" - -#ifdef MAVLINK_USE_CXX_NAMESPACE -namespace mavlink { -#endif - -/* - * Internal function to give access to the channel status for each channel - */ -#ifndef MAVLINK_GET_CHANNEL_STATUS -MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) -{ -#ifdef MAVLINK_EXTERNAL_RX_STATUS - // No m_mavlink_status array defined in function, - // has to be defined externally -#else - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; -#endif - return &m_mavlink_status[chan]; -} -#endif - -/* - * Internal function to give access to the channel buffer for each channel - */ -#ifndef MAVLINK_GET_CHANNEL_BUFFER -MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) -{ - -#ifdef MAVLINK_EXTERNAL_RX_BUFFER - // No m_mavlink_buffer array defined in function, - // has to be defined externally -#else - static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; -#endif - return &m_mavlink_buffer[chan]; -} -#endif // MAVLINK_GET_CHANNEL_BUFFER - -/** - * @brief Reset the status of a channel. - */ -MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan) -{ - mavlink_status_t *status = mavlink_get_channel_status(chan); - status->parse_state = MAVLINK_PARSE_STATE_IDLE; -} - -/** - * @brief create a signature block for a packet - */ -MAVLINK_HELPER uint8_t mavlink_sign_packet(mavlink_signing_t *signing, - uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN], - const uint8_t *header, uint8_t header_len, - const uint8_t *packet, uint8_t packet_len, - const uint8_t crc[2]) -{ - mavlink_sha256_ctx ctx; - union { - uint64_t t64; - uint8_t t8[8]; - } tstamp; - if (signing == NULL || !(signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) { - return 0; - } - signature[0] = signing->link_id; - tstamp.t64 = signing->timestamp; - memcpy(&signature[1], tstamp.t8, 6); - signing->timestamp++; - - mavlink_sha256_init(&ctx); - mavlink_sha256_update(&ctx, signing->secret_key, sizeof(signing->secret_key)); - mavlink_sha256_update(&ctx, header, header_len); - mavlink_sha256_update(&ctx, packet, packet_len); - mavlink_sha256_update(&ctx, crc, 2); - mavlink_sha256_update(&ctx, signature, 7); - mavlink_sha256_final_48(&ctx, &signature[7]); - - return MAVLINK_SIGNATURE_BLOCK_LEN; -} - -/** - * return new packet length for trimming payload of any trailing zero - * bytes. Used in MAVLink2 to give simple support for variable length - * arrays. - */ -MAVLINK_HELPER uint8_t _mav_trim_payload(const char *payload, uint8_t length) -{ - while (length > 1 && payload[length-1] == 0) { - length--; - } - return length; -} - -/** - * @brief check a signature block for a packet - */ -MAVLINK_HELPER bool mavlink_signature_check(mavlink_signing_t *signing, - mavlink_signing_streams_t *signing_streams, - const mavlink_message_t *msg) -{ - if (signing == NULL) { - return true; - } - const uint8_t *p = (const uint8_t *)&msg->magic; - const uint8_t *psig = msg->signature; - const uint8_t *incoming_signature = psig+7; - mavlink_sha256_ctx ctx; - uint8_t signature[6]; - uint16_t i; - - mavlink_sha256_init(&ctx); - mavlink_sha256_update(&ctx, signing->secret_key, sizeof(signing->secret_key)); - mavlink_sha256_update(&ctx, p, MAVLINK_CORE_HEADER_LEN+1+msg->len); - mavlink_sha256_update(&ctx, msg->ck, 2); - mavlink_sha256_update(&ctx, psig, 1+6); - mavlink_sha256_final_48(&ctx, signature); - if (memcmp(signature, incoming_signature, 6) != 0) { - return false; - } - - // now check timestamp - union tstamp { - uint64_t t64; - uint8_t t8[8]; - } tstamp; - uint8_t link_id = psig[0]; - tstamp.t64 = 0; - memcpy(tstamp.t8, psig+1, 6); - - if (signing_streams == NULL) { - return false; - } - - // find stream - for (i=0; inum_signing_streams; i++) { - if (msg->sysid == signing_streams->stream[i].sysid && - msg->compid == signing_streams->stream[i].compid && - link_id == signing_streams->stream[i].link_id) { - break; - } - } - if (i == signing_streams->num_signing_streams) { - if (signing_streams->num_signing_streams >= MAVLINK_MAX_SIGNING_STREAMS) { - // over max number of streams - return false; - } - // new stream. Only accept if timestamp is not more than 1 minute old - if (tstamp.t64 + 6000*1000UL < signing->timestamp) { - return false; - } - // add new stream - signing_streams->stream[i].sysid = msg->sysid; - signing_streams->stream[i].compid = msg->compid; - signing_streams->stream[i].link_id = link_id; - signing_streams->num_signing_streams++; - } else { - union tstamp last_tstamp; - last_tstamp.t64 = 0; - memcpy(last_tstamp.t8, signing_streams->stream[i].timestamp_bytes, 6); - if (tstamp.t64 <= last_tstamp.t64) { - // repeating old timestamp - return false; - } - } - - // remember last timestamp - memcpy(signing_streams->stream[i].timestamp_bytes, psig+1, 6); - - // our next timestamp must be at least this timestamp - if (tstamp.t64 > signing->timestamp) { - signing->timestamp = tstamp.t64; - } - return true; -} - - -/** - * @brief Finalize a MAVLink message with channel assignment - * - * This function calculates the checksum and sets length and aircraft id correctly. - * It assumes that the message id and the payload are already correctly set. This function - * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack - * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. - * - * @param msg Message to finalize - * @param system_id Id of the sending (this) system, 1-127 - * @param length Message length - */ -MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - mavlink_status_t* status, uint8_t min_length, uint8_t length, uint8_t crc_extra) -{ - bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0; - bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING); - uint8_t signature_len = signing? MAVLINK_SIGNATURE_BLOCK_LEN : 0; - uint8_t header_len = MAVLINK_CORE_HEADER_LEN+1; - uint8_t buf[MAVLINK_CORE_HEADER_LEN+1]; - if (mavlink1) { - msg->magic = MAVLINK_STX_MAVLINK1; - header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN+1; - } else { - msg->magic = MAVLINK_STX; - } - msg->len = mavlink1?min_length:_mav_trim_payload(_MAV_PAYLOAD(msg), length); - msg->sysid = system_id; - msg->compid = component_id; - msg->incompat_flags = 0; - if (signing) { - msg->incompat_flags |= MAVLINK_IFLAG_SIGNED; - } - msg->compat_flags = 0; - msg->seq = status->current_tx_seq; - status->current_tx_seq = status->current_tx_seq + 1; - - // form the header as a byte array for the crc - buf[0] = msg->magic; - buf[1] = msg->len; - if (mavlink1) { - buf[2] = msg->seq; - buf[3] = msg->sysid; - buf[4] = msg->compid; - buf[5] = msg->msgid & 0xFF; - } else { - buf[2] = msg->incompat_flags; - buf[3] = msg->compat_flags; - buf[4] = msg->seq; - buf[5] = msg->sysid; - buf[6] = msg->compid; - buf[7] = msg->msgid & 0xFF; - buf[8] = (msg->msgid >> 8) & 0xFF; - buf[9] = (msg->msgid >> 16) & 0xFF; - } - - msg->checksum = crc_calculate(&buf[1], header_len-1); - crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len); - crc_accumulate(crc_extra, &msg->checksum); - mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF); - mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8); - - if (signing) { - mavlink_sign_packet(status->signing, - msg->signature, - (const uint8_t *)buf, header_len, - (const uint8_t *)_MAV_PAYLOAD(msg), msg->len, - (const uint8_t *)_MAV_PAYLOAD(msg)+(uint16_t)msg->len); - } - - return msg->len + header_len + 2 + signature_len; -} - -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra) -{ - mavlink_status_t *status = mavlink_get_channel_status(chan); - return mavlink_finalize_message_buffer(msg, system_id, component_id, status, min_length, length, crc_extra); -} - -/** - * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel - */ -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t min_length, uint8_t length, uint8_t crc_extra) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, min_length, length, crc_extra); -} - -static inline void _mav_parse_error(mavlink_status_t *status) -{ - status->parse_error++; -} - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); - -/** - * @brief Finalize a MAVLink message with channel assignment and send - */ -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint32_t msgid, - const char *packet, - uint8_t min_length, uint8_t length, uint8_t crc_extra) -{ - uint16_t checksum; - uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; - uint8_t ck[2]; - mavlink_status_t *status = mavlink_get_channel_status(chan); - uint8_t header_len = MAVLINK_CORE_HEADER_LEN; - uint8_t signature_len = 0; - uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN]; - bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0; - bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING); - - if (mavlink1) { - length = min_length; - if (msgid > 255) { - // can't send 16 bit messages - _mav_parse_error(status); - return; - } - header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN; - buf[0] = MAVLINK_STX_MAVLINK1; - buf[1] = length; - buf[2] = status->current_tx_seq; - buf[3] = mavlink_system.sysid; - buf[4] = mavlink_system.compid; - buf[5] = msgid & 0xFF; - } else { - uint8_t incompat_flags = 0; - if (signing) { - incompat_flags |= MAVLINK_IFLAG_SIGNED; - } - length = _mav_trim_payload(packet, length); - buf[0] = MAVLINK_STX; - buf[1] = length; - buf[2] = incompat_flags; - buf[3] = 0; // compat_flags - buf[4] = status->current_tx_seq; - buf[5] = mavlink_system.sysid; - buf[6] = mavlink_system.compid; - buf[7] = msgid & 0xFF; - buf[8] = (msgid >> 8) & 0xFF; - buf[9] = (msgid >> 16) & 0xFF; - } - status->current_tx_seq++; - checksum = crc_calculate((const uint8_t*)&buf[1], header_len); - crc_accumulate_buffer(&checksum, packet, length); - crc_accumulate(crc_extra, &checksum); - ck[0] = (uint8_t)(checksum & 0xFF); - ck[1] = (uint8_t)(checksum >> 8); - - if (signing) { - // possibly add a signature - signature_len = mavlink_sign_packet(status->signing, signature, buf, header_len+1, - (const uint8_t *)packet, length, ck); - } - - MAVLINK_START_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len); - _mavlink_send_uart(chan, (const char *)buf, header_len+1); - _mavlink_send_uart(chan, packet, length); - _mavlink_send_uart(chan, (const char *)ck, 2); - if (signature_len != 0) { - _mavlink_send_uart(chan, (const char *)signature, signature_len); - } - MAVLINK_END_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len); -} - -/** - * @brief re-send a message over a uart channel - * this is more stack efficient than re-marshalling the message - * If the message is signed then the original signature is also sent - */ -MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg) -{ - uint8_t ck[2]; - - ck[0] = (uint8_t)(msg->checksum & 0xFF); - ck[1] = (uint8_t)(msg->checksum >> 8); - // XXX use the right sequence here - - uint8_t header_len; - uint8_t signature_len; - - if (msg->magic == MAVLINK_STX_MAVLINK1) { - header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1; - signature_len = 0; - MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len); - // we can't send the structure directly as it has extra mavlink2 elements in it - uint8_t buf[MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1]; - buf[0] = msg->magic; - buf[1] = msg->len; - buf[2] = msg->seq; - buf[3] = msg->sysid; - buf[4] = msg->compid; - buf[5] = msg->msgid & 0xFF; - _mavlink_send_uart(chan, (const char*)buf, header_len); - } else { - header_len = MAVLINK_CORE_HEADER_LEN + 1; - signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0; - MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len); - uint8_t buf[MAVLINK_CORE_HEADER_LEN + 1]; - buf[0] = msg->magic; - buf[1] = msg->len; - buf[2] = msg->incompat_flags; - buf[3] = msg->compat_flags; - buf[4] = msg->seq; - buf[5] = msg->sysid; - buf[6] = msg->compid; - buf[7] = msg->msgid & 0xFF; - buf[8] = (msg->msgid >> 8) & 0xFF; - buf[9] = (msg->msgid >> 16) & 0xFF; - _mavlink_send_uart(chan, (const char *)buf, header_len); - } - _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len); - _mavlink_send_uart(chan, (const char *)ck, 2); - if (signature_len != 0) { - _mavlink_send_uart(chan, (const char *)msg->signature, MAVLINK_SIGNATURE_BLOCK_LEN); - } - MAVLINK_END_UART_SEND(chan, header_len + msg->len + 2 + signature_len); -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -/** - * @brief Pack a message to send it over a serial byte stream - */ -MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buf, const mavlink_message_t *msg) -{ - uint8_t signature_len, header_len; - uint8_t *ck; - uint8_t length = msg->len; - - if (msg->magic == MAVLINK_STX_MAVLINK1) { - signature_len = 0; - header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN; - buf[0] = msg->magic; - buf[1] = length; - buf[2] = msg->seq; - buf[3] = msg->sysid; - buf[4] = msg->compid; - buf[5] = msg->msgid & 0xFF; - memcpy(&buf[6], _MAV_PAYLOAD(msg), msg->len); - ck = buf + header_len + 1 + (uint16_t)msg->len; - } else { - length = _mav_trim_payload(_MAV_PAYLOAD(msg), length); - header_len = MAVLINK_CORE_HEADER_LEN; - buf[0] = msg->magic; - buf[1] = length; - buf[2] = msg->incompat_flags; - buf[3] = msg->compat_flags; - buf[4] = msg->seq; - buf[5] = msg->sysid; - buf[6] = msg->compid; - buf[7] = msg->msgid & 0xFF; - buf[8] = (msg->msgid >> 8) & 0xFF; - buf[9] = (msg->msgid >> 16) & 0xFF; - memcpy(&buf[10], _MAV_PAYLOAD(msg), length); - ck = buf + header_len + 1 + (uint16_t)length; - signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0; - } - ck[0] = (uint8_t)(msg->checksum & 0xFF); - ck[1] = (uint8_t)(msg->checksum >> 8); - if (signature_len > 0) { - memcpy(&ck[2], msg->signature, signature_len); - } - - return header_len + 1 + 2 + (uint16_t)length + (uint16_t)signature_len; -} - -union __mavlink_bitfield { - uint8_t uint8; - int8_t int8; - uint16_t uint16; - int16_t int16; - uint32_t uint32; - int32_t int32; -}; - - -MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) -{ - crc_init(&msg->checksum); -} - -MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) -{ - crc_accumulate(c, &msg->checksum); -} - -/* - return the crc_entry value for a msgid -*/ -#ifndef MAVLINK_GET_MSG_ENTRY -MAVLINK_HELPER const mavlink_msg_entry_t *mavlink_get_msg_entry(uint32_t msgid) -{ - static const mavlink_msg_entry_t mavlink_message_crcs[] = MAVLINK_MESSAGE_CRCS; - /* - use a bisection search to find the right entry. A perfect hash may be better - Note that this assumes the table is sorted by msgid - */ - uint32_t low=0, high=sizeof(mavlink_message_crcs)/sizeof(mavlink_message_crcs[0]); - while (low < high) { - uint32_t mid = (low+1+high)/2; - if (msgid < mavlink_message_crcs[mid].msgid) { - high = mid-1; - continue; - } - if (msgid > mavlink_message_crcs[mid].msgid) { - low = mid; - continue; - } - low = mid; - break; - } - if (mavlink_message_crcs[low].msgid != msgid) { - // msgid is not in the table - return NULL; - } - return &mavlink_message_crcs[low]; -} -#endif // MAVLINK_GET_MSG_ENTRY - -/* - return the crc_extra value for a message -*/ -MAVLINK_HELPER uint8_t mavlink_get_crc_extra(const mavlink_message_t *msg) -{ - const mavlink_msg_entry_t *e = mavlink_get_msg_entry(msg->msgid); - return e?e->crc_extra:0; -} - -/* - return the expected message length -*/ -#define MAVLINK_HAVE_EXPECTED_MESSAGE_LENGTH -MAVLINK_HELPER uint8_t mavlink_expected_message_length(const mavlink_message_t *msg) -{ - const mavlink_msg_entry_t *e = mavlink_get_msg_entry(msg->msgid); - return e?e->msg_len:0; -} - -/** - * This is a varient of mavlink_frame_char() but with caller supplied - * parsing buffers. It is useful when you want to create a MAVLink - * parser in a library that doesn't use any global variables - * - * @param rxmsg parsing message buffer - * @param status parsing starus buffer - * @param c The char to parse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @param returnStats if a message was decoded, this is filled with the channel's stats - * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC - * - * A typical use scenario of this function call is: - * - * @code - * #include - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, - mavlink_status_t* status, - uint8_t c, - mavlink_message_t* r_message, - mavlink_status_t* r_mavlink_status) -{ - /* Enable this option to check the length of each message. - This allows invalid messages to be caught much sooner. Use if the transmission - medium is prone to missing (or extra) characters (e.g. a radio that fades in - and out). Only use if the channel will only contain messages types listed in - the headers. - */ -#ifdef MAVLINK_CHECK_MESSAGE_LENGTH -#ifndef MAVLINK_MESSAGE_LENGTH - static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS; -#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid] -#endif -#endif - - int bufferIndex = 0; - - status->msg_received = MAVLINK_FRAMING_INCOMPLETE; - - switch (status->parse_state) - { - case MAVLINK_PARSE_STATE_UNINIT: - case MAVLINK_PARSE_STATE_IDLE: - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - rxmsg->magic = c; - status->flags &= ~MAVLINK_STATUS_FLAG_IN_MAVLINK1; - mavlink_start_checksum(rxmsg); - } else if (c == MAVLINK_STX_MAVLINK1) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - rxmsg->magic = c; - status->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1; - mavlink_start_checksum(rxmsg); - } - break; - - case MAVLINK_PARSE_STATE_GOT_STX: - if (status->msg_received -/* Support shorter buffers than the - default maximum packet size */ -#if (MAVLINK_MAX_PAYLOAD_LEN < 255) - || c > MAVLINK_MAX_PAYLOAD_LEN -#endif - ) - { - status->buffer_overrun++; - _mav_parse_error(status); - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - } - else - { - // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 - rxmsg->len = c; - status->packet_idx = 0; - mavlink_update_checksum(rxmsg, c); - if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) { - rxmsg->incompat_flags = 0; - rxmsg->compat_flags = 0; - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS; - } else { - status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; - } - } - break; - - case MAVLINK_PARSE_STATE_GOT_LENGTH: - rxmsg->incompat_flags = c; - if ((rxmsg->incompat_flags & ~MAVLINK_IFLAG_MASK) != 0) { - // message includes an incompatible feature flag - _mav_parse_error(status); - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - break; - } - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS; - break; - - case MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS: - rxmsg->compat_flags = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS; - break; - - case MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS: - rxmsg->seq = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; - break; - - case MAVLINK_PARSE_STATE_GOT_SEQ: - rxmsg->sysid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; - break; - - case MAVLINK_PARSE_STATE_GOT_SYSID: - rxmsg->compid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; - break; - - case MAVLINK_PARSE_STATE_GOT_COMPID: - rxmsg->msgid = c; - mavlink_update_checksum(rxmsg, c); - if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) { - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3; -#ifdef MAVLINK_CHECK_MESSAGE_LENGTH - if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(rxmsg->msgid)) - { - _mav_parse_error(status); - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - break; - } -#endif - } else { - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID1; - } - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID1: - rxmsg->msgid |= c<<8; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID2; - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID2: - rxmsg->msgid |= c<<16; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3; -#ifdef MAVLINK_CHECK_MESSAGE_LENGTH - if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(rxmsg->msgid)) - { - _mav_parse_error(status); - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - break; - } -#endif - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID3: - _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; - mavlink_update_checksum(rxmsg, c); - if (status->packet_idx == rxmsg->len) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - break; - - case MAVLINK_PARSE_STATE_GOT_PAYLOAD: { - const mavlink_msg_entry_t *e = mavlink_get_msg_entry(rxmsg->msgid); - uint8_t crc_extra = e?e->crc_extra:0; - mavlink_update_checksum(rxmsg, crc_extra); - if (c != (rxmsg->checksum & 0xFF)) { - status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1; - } else { - status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; - } - rxmsg->ck[0] = c; - - // zero-fill the packet to cope with short incoming packets - if (e && status->packet_idx < e->msg_len) { - memset(&_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx], 0, e->msg_len - status->packet_idx); - } - break; - } - - case MAVLINK_PARSE_STATE_GOT_CRC1: - case MAVLINK_PARSE_STATE_GOT_BAD_CRC1: - if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) { - // got a bad CRC message - status->msg_received = MAVLINK_FRAMING_BAD_CRC; - } else { - // Successfully got message - status->msg_received = MAVLINK_FRAMING_OK; - } - rxmsg->ck[1] = c; - - if (rxmsg->incompat_flags & MAVLINK_IFLAG_SIGNED) { - status->parse_state = MAVLINK_PARSE_STATE_SIGNATURE_WAIT; - status->signature_wait = MAVLINK_SIGNATURE_BLOCK_LEN; - - // If the CRC is already wrong, don't overwrite msg_received, - // otherwise we can end up with garbage flagged as valid. - if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) { - status->msg_received = MAVLINK_FRAMING_INCOMPLETE; - } - } else { - if (status->signing && - (status->signing->accept_unsigned_callback == NULL || - !status->signing->accept_unsigned_callback(status, rxmsg->msgid))) { - - // If the CRC is already wrong, don't overwrite msg_received. - if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) { - status->msg_received = MAVLINK_FRAMING_BAD_SIGNATURE; - } - } - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); - } - break; - case MAVLINK_PARSE_STATE_SIGNATURE_WAIT: - rxmsg->signature[MAVLINK_SIGNATURE_BLOCK_LEN-status->signature_wait] = c; - status->signature_wait--; - if (status->signature_wait == 0) { - // we have the whole signature, check it is OK - bool sig_ok = mavlink_signature_check(status->signing, status->signing_streams, rxmsg); - if (!sig_ok && - (status->signing->accept_unsigned_callback && - status->signing->accept_unsigned_callback(status, rxmsg->msgid))) { - // accepted via application level override - sig_ok = true; - } - if (sig_ok) { - status->msg_received = MAVLINK_FRAMING_OK; - } else { - status->msg_received = MAVLINK_FRAMING_BAD_SIGNATURE; - } - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); - } - break; - } - - bufferIndex++; - // If a message has been sucessfully decoded, check index - if (status->msg_received == MAVLINK_FRAMING_OK) - { - //while(status->current_seq != rxmsg->seq) - //{ - // status->packet_rx_drop_count++; - // status->current_seq++; - //} - status->current_rx_seq = rxmsg->seq; - // Initial condition: If no packet has been received so far, drop count is undefined - if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; - // Count this packet as received - status->packet_rx_success_count++; - } - - r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg - r_mavlink_status->parse_state = status->parse_state; - r_mavlink_status->packet_idx = status->packet_idx; - r_mavlink_status->current_rx_seq = status->current_rx_seq+1; - r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; - r_mavlink_status->packet_rx_drop_count = status->parse_error; - r_mavlink_status->flags = status->flags; - status->parse_error = 0; - - if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) { - /* - the CRC came out wrong. We now need to overwrite the - msg CRC with the one on the wire so that if the - caller decides to forward the message anyway that - mavlink_msg_to_send_buffer() won't overwrite the - checksum - */ - r_message->checksum = rxmsg->ck[0] | (rxmsg->ck[1]<<8); - } - - return status->msg_received; -} - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. This function will return 0, 1 or - * 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC) - * - * Messages are parsed into an internal buffer (one for each channel). When a complete - * message is received it is copies into *returnMsg and the channel's status is - * copied into *returnStats. - * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to parse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @param returnStats if a message was decoded, this is filled with the channel's stats - * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC - * - * A typical use scenario of this function call is: - * - * @code - * #include - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -{ - return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan), - mavlink_get_channel_status(chan), - c, - r_message, - r_mavlink_status); -} - -/** - * Set the protocol version - */ -MAVLINK_HELPER void mavlink_set_proto_version(uint8_t chan, unsigned int version) -{ - mavlink_status_t *status = mavlink_get_channel_status(chan); - if (version > 1) { - status->flags &= ~(MAVLINK_STATUS_FLAG_OUT_MAVLINK1); - } else { - status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1; - } -} - -/** - * Get the protocol version - * - * @return 1 for v1, 2 for v2 - */ -MAVLINK_HELPER unsigned int mavlink_get_proto_version(uint8_t chan) -{ - mavlink_status_t *status = mavlink_get_channel_status(chan); - if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) > 0) { - return 1; - } else { - return 2; - } -} - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. This function will return 0 or 1. - * - * Messages are parsed into an internal buffer (one for each channel). When a complete - * message is received it is copies into *returnMsg and the channel's status is - * copied into *returnStats. - * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to parse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @param returnStats if a message was decoded, this is filled with the channel's stats - * @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC - * - * A typical use scenario of this function call is: - * - * @code - * #include - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_parse_char(chan, byte, &msg)) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -{ - uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status); - if (msg_received == MAVLINK_FRAMING_BAD_CRC || - msg_received == MAVLINK_FRAMING_BAD_SIGNATURE) { - // we got a bad CRC. Treat as a parse failure - mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); - mavlink_status_t* status = mavlink_get_channel_status(chan); - _mav_parse_error(status); - status->msg_received = MAVLINK_FRAMING_INCOMPLETE; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - return 0; - } - return msg_received; -} - -/** - * @brief Put a bitfield of length 1-32 bit into the buffer - * - * @param b the value to add, will be encoded in the bitfield - * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. - * @param packet_index the position in the packet (the index of the first byte to use) - * @param bit_index the position in the byte (the index of the first bit to use) - * @param buffer packet buffer to write into - * @return new position of the last used byte in the buffer - */ -MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) -{ - uint16_t bits_remain = bits; - // Transform number into network order - int32_t v; - uint8_t i_bit_index, i_byte_index, curr_bits_n; -#if MAVLINK_NEED_BYTE_SWAP - union { - int32_t i; - uint8_t b[4]; - } bin, bout; - bin.i = b; - bout.b[0] = bin.b[3]; - bout.b[1] = bin.b[2]; - bout.b[2] = bin.b[1]; - bout.b[3] = bin.b[0]; - v = bout.i; -#else - v = b; -#endif - - // buffer in - // 01100000 01000000 00000000 11110001 - // buffer out - // 11110001 00000000 01000000 01100000 - - // Existing partly filled byte (four free slots) - // 0111xxxx - - // Mask n free bits - // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 - // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 - - // Shift n bits into the right position - // out = in >> n; - - // Mask and shift bytes - i_bit_index = bit_index; - i_byte_index = packet_index; - if (bit_index > 0) - { - // If bits were available at start, they were available - // in the byte before the current index - i_byte_index--; - } - - // While bits have not been packed yet - while (bits_remain > 0) - { - // Bits still have to be packed - // there can be more than 8 bits, so - // we might have to pack them into more than one byte - - // First pack everything we can into the current 'open' byte - //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 - //FIXME - if (bits_remain <= (uint8_t)(8 - i_bit_index)) - { - // Enough space - curr_bits_n = (uint8_t)bits_remain; - } - else - { - curr_bits_n = (8 - i_bit_index); - } - - // Pack these n bits into the current byte - // Mask out whatever was at that position with ones (xxx11111) - buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); - // Put content to this position, by masking out the non-used part - buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); - - // Increment the bit index - i_bit_index += curr_bits_n; - - // Now proceed to the next byte, if necessary - bits_remain -= curr_bits_n; - if (bits_remain > 0) - { - // Offer another 8 bits / one byte - i_byte_index++; - i_bit_index = 0; - } - } - - *r_bit_index = i_bit_index; - // If a partly filled byte is present, mark this as consumed - if (i_bit_index != 7) i_byte_index++; - return i_byte_index - packet_index; -} - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -// To make MAVLink work on your MCU, define comm_send_ch() if you wish -// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a -// whole packet at a time - -/* - -#include "mavlink_types.h" - -void comm_send_ch(mavlink_channel_t chan, uint8_t ch) -{ - if (chan == MAVLINK_COMM_0) - { - uart0_transmit(ch); - } - if (chan == MAVLINK_COMM_1) - { - uart1_transmit(ch); - } -} - */ - -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) -{ -#ifdef MAVLINK_SEND_UART_BYTES - /* this is the more efficient approach, if the platform - defines it */ - MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len); -#else - /* fallback to one byte at a time */ - uint16_t i; - for (i = 0; i < len; i++) { - comm_send_ch(chan, (uint8_t)buf[i]); - } -#endif -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -#ifdef MAVLINK_USE_CXX_NAMESPACE -} // namespace mavlink -#endif diff --git a/include/mavlink/v2.0/mavlink_sha256.h b/include/mavlink/v2.0/mavlink_sha256.h deleted file mode 100644 index 64fb976..0000000 --- a/include/mavlink/v2.0/mavlink_sha256.h +++ /dev/null @@ -1,252 +0,0 @@ -#pragma once - -/* - sha-256 implementation for MAVLink based on Heimdal sources, with - modifications to suit mavlink headers - */ -/* - * Copyright (c) 1995 - 2001 Kungliga Tekniska Högskolan - * (Royal Institute of Technology, Stockholm, Sweden). - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * - * 3. Neither the name of the Institute nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND - * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS - * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) - * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY - * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF - * SUCH DAMAGE. - */ - -/* - allow implementation to provide their own sha256 with the same API -*/ -#ifndef HAVE_MAVLINK_SHA256 - -#ifdef MAVLINK_USE_CXX_NAMESPACE -namespace mavlink { -#endif - -#ifndef MAVLINK_HELPER -#define MAVLINK_HELPER -#endif - -typedef struct { - unsigned int sz[2]; - uint32_t counter[8]; - union { - unsigned char save_bytes[64]; - uint32_t save_u32[16]; - } u; -} mavlink_sha256_ctx; - -#define Ch(x,y,z) (((x) & (y)) ^ ((~(x)) & (z))) -#define Maj(x,y,z) (((x) & (y)) ^ ((x) & (z)) ^ ((y) & (z))) - -#define ROTR(x,n) (((x)>>(n)) | ((x) << (32 - (n)))) - -#define Sigma0(x) (ROTR(x,2) ^ ROTR(x,13) ^ ROTR(x,22)) -#define Sigma1(x) (ROTR(x,6) ^ ROTR(x,11) ^ ROTR(x,25)) -#define sigma0(x) (ROTR(x,7) ^ ROTR(x,18) ^ ((x)>>3)) -#define sigma1(x) (ROTR(x,17) ^ ROTR(x,19) ^ ((x)>>10)) - -#define A m->counter[0] -#define B m->counter[1] -#define C m->counter[2] -#define D m->counter[3] -#define E m->counter[4] -#define F m->counter[5] -#define G m->counter[6] -#define H m->counter[7] - -static const uint32_t mavlink_sha256_constant_256[64] = { - 0x428a2f98, 0x71374491, 0xb5c0fbcf, 0xe9b5dba5, - 0x3956c25b, 0x59f111f1, 0x923f82a4, 0xab1c5ed5, - 0xd807aa98, 0x12835b01, 0x243185be, 0x550c7dc3, - 0x72be5d74, 0x80deb1fe, 0x9bdc06a7, 0xc19bf174, - 0xe49b69c1, 0xefbe4786, 0x0fc19dc6, 0x240ca1cc, - 0x2de92c6f, 0x4a7484aa, 0x5cb0a9dc, 0x76f988da, - 0x983e5152, 0xa831c66d, 0xb00327c8, 0xbf597fc7, - 0xc6e00bf3, 0xd5a79147, 0x06ca6351, 0x14292967, - 0x27b70a85, 0x2e1b2138, 0x4d2c6dfc, 0x53380d13, - 0x650a7354, 0x766a0abb, 0x81c2c92e, 0x92722c85, - 0xa2bfe8a1, 0xa81a664b, 0xc24b8b70, 0xc76c51a3, - 0xd192e819, 0xd6990624, 0xf40e3585, 0x106aa070, - 0x19a4c116, 0x1e376c08, 0x2748774c, 0x34b0bcb5, - 0x391c0cb3, 0x4ed8aa4a, 0x5b9cca4f, 0x682e6ff3, - 0x748f82ee, 0x78a5636f, 0x84c87814, 0x8cc70208, - 0x90befffa, 0xa4506ceb, 0xbef9a3f7, 0xc67178f2 -}; - -MAVLINK_HELPER void mavlink_sha256_init(mavlink_sha256_ctx *m) -{ - m->sz[0] = 0; - m->sz[1] = 0; - A = 0x6a09e667; - B = 0xbb67ae85; - C = 0x3c6ef372; - D = 0xa54ff53a; - E = 0x510e527f; - F = 0x9b05688c; - G = 0x1f83d9ab; - H = 0x5be0cd19; -} - -static inline void mavlink_sha256_calc(mavlink_sha256_ctx *m, uint32_t *in) -{ - uint32_t AA, BB, CC, DD, EE, FF, GG, HH; - uint32_t data[64]; - int i; - - AA = A; - BB = B; - CC = C; - DD = D; - EE = E; - FF = F; - GG = G; - HH = H; - - for (i = 0; i < 16; ++i) - data[i] = in[i]; - for (i = 16; i < 64; ++i) - data[i] = sigma1(data[i-2]) + data[i-7] + - sigma0(data[i-15]) + data[i - 16]; - - for (i = 0; i < 64; i++) { - uint32_t T1, T2; - - T1 = HH + Sigma1(EE) + Ch(EE, FF, GG) + mavlink_sha256_constant_256[i] + data[i]; - T2 = Sigma0(AA) + Maj(AA,BB,CC); - - HH = GG; - GG = FF; - FF = EE; - EE = DD + T1; - DD = CC; - CC = BB; - BB = AA; - AA = T1 + T2; - } - - A += AA; - B += BB; - C += CC; - D += DD; - E += EE; - F += FF; - G += GG; - H += HH; -} - -MAVLINK_HELPER void mavlink_sha256_update(mavlink_sha256_ctx *m, const void *v, uint32_t len) -{ - const unsigned char *p = (const unsigned char *)v; - uint32_t old_sz = m->sz[0]; - uint32_t offset; - - m->sz[0] += len * 8; - if (m->sz[0] < old_sz) - ++m->sz[1]; - offset = (old_sz / 8) % 64; - while(len > 0){ - uint32_t l = 64 - offset; - if (len < l) { - l = len; - } - memcpy(m->u.save_bytes + offset, p, l); - offset += l; - p += l; - len -= l; - if(offset == 64){ - int i; - uint32_t current[16]; - const uint32_t *u = m->u.save_u32; - for (i = 0; i < 16; i++){ - const uint8_t *p1 = (const uint8_t *)&u[i]; - uint8_t *p2 = (uint8_t *)¤t[i]; - p2[0] = p1[3]; - p2[1] = p1[2]; - p2[2] = p1[1]; - p2[3] = p1[0]; - } - mavlink_sha256_calc(m, current); - offset = 0; - } - } -} - -/* - get first 48 bits of final sha256 hash - */ -MAVLINK_HELPER void mavlink_sha256_final_48(mavlink_sha256_ctx *m, uint8_t result[6]) -{ - unsigned char zeros[72]; - unsigned offset = (m->sz[0] / 8) % 64; - unsigned int dstart = (120 - offset - 1) % 64 + 1; - uint8_t *p = (uint8_t *)&m->counter[0]; - - *zeros = 0x80; - memset (zeros + 1, 0, sizeof(zeros) - 1); - zeros[dstart+7] = (m->sz[0] >> 0) & 0xff; - zeros[dstart+6] = (m->sz[0] >> 8) & 0xff; - zeros[dstart+5] = (m->sz[0] >> 16) & 0xff; - zeros[dstart+4] = (m->sz[0] >> 24) & 0xff; - zeros[dstart+3] = (m->sz[1] >> 0) & 0xff; - zeros[dstart+2] = (m->sz[1] >> 8) & 0xff; - zeros[dstart+1] = (m->sz[1] >> 16) & 0xff; - zeros[dstart+0] = (m->sz[1] >> 24) & 0xff; - - mavlink_sha256_update(m, zeros, dstart + 8); - - // this ordering makes the result consistent with taking the first - // 6 bytes of more conventional sha256 functions. It assumes - // little-endian ordering of m->counter - result[0] = p[3]; - result[1] = p[2]; - result[2] = p[1]; - result[3] = p[0]; - result[4] = p[7]; - result[5] = p[6]; -} - -// prevent conflicts with users of the header -#undef A -#undef B -#undef C -#undef D -#undef E -#undef F -#undef G -#undef H -#undef Ch -#undef ROTR -#undef Sigma0 -#undef Sigma1 -#undef sigma0 -#undef sigma1 - -#ifdef MAVLINK_USE_CXX_NAMESPACE -} // namespace mavlink -#endif - -#endif // HAVE_MAVLINK_SHA256 diff --git a/include/mavlink/v2.0/mavlink_types.h b/include/mavlink/v2.0/mavlink_types.h deleted file mode 100644 index a95592e..0000000 --- a/include/mavlink/v2.0/mavlink_types.h +++ /dev/null @@ -1,298 +0,0 @@ -#pragma once - -// Visual Studio versions before 2010 don't have stdint.h, so we just error out. -#if (defined _MSC_VER) && (_MSC_VER < 1600) -#error "The C-MAVLink implementation requires Visual Studio 2010 or greater" -#endif - -#include -#include - -#ifdef MAVLINK_USE_CXX_NAMESPACE -namespace mavlink { -#endif - -// Macro to define packed structures -#ifdef __GNUC__ - #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed)) -#else - #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) -#endif - -#ifndef MAVLINK_MAX_PAYLOAD_LEN -// it is possible to override this, but be careful! -#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length -#endif - -#define MAVLINK_CORE_HEADER_LEN 9 ///< Length of core header (of the comm. layer) -#define MAVLINK_CORE_HEADER_MAVLINK1_LEN 5 ///< Length of MAVLink1 core header (of the comm. layer) -#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and stx -#define MAVLINK_NUM_CHECKSUM_BYTES 2 -#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) - -#define MAVLINK_SIGNATURE_BLOCK_LEN 13 - -#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN) ///< Maximum packet length - -/** - * Old-style 4 byte param union - * - * This struct is the data format to be used when sending - * parameters. The parameter should be copied to the native - * type (without type conversion) - * and re-instanted on the receiving side using the - * native type as well. - */ -MAVPACKED( -typedef struct param_union { - union { - float param_float; - int32_t param_int32; - uint32_t param_uint32; - 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; - - -/** - * New-style 8 byte param union - * mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering. - * The mavlink_param_union_double_t will be treated as a little-endian structure. - * - * If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero. - * The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the - * lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union. - * The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above, - * as bitfield ordering isn’t consistent between platforms. The above is intended to be for gcc on x86, - * which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number, - * and the bits pulled out using the shifts/masks. -*/ -MAVPACKED( -typedef struct param_union_extended { - union { - struct { - uint8_t is_double:1; - uint8_t mavlink_type:7; - union { - char c; - uint8_t uint8; - int8_t int8; - uint16_t uint16; - int16_t int16; - uint32_t uint32; - int32_t int32; - float f; - uint8_t align[7]; - }; - }; - uint8_t data[8]; - }; -}) mavlink_param_union_double_t; - -/** - * This structure is required to make the mavlink_send_xxx convenience functions - * work, as it tells the library what the current system and component ID are. - */ -MAVPACKED( -typedef struct __mavlink_system { - uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function -}) mavlink_system_t; - -MAVPACKED( -typedef struct __mavlink_message { - uint16_t checksum; ///< sent at end of packet - uint8_t magic; ///< protocol magic marker - uint8_t len; ///< Length of payload - uint8_t incompat_flags; ///< flags that must be understood - uint8_t compat_flags; ///< flags that can be ignored if not understood - uint8_t seq; ///< Sequence of packet - uint8_t sysid; ///< ID of message sender system/aircraft - uint8_t compid; ///< ID of the message sender component - uint32_t msgid:24; ///< ID of message in payload - uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; - uint8_t ck[2]; ///< incoming checksum bytes - uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN]; -}) mavlink_message_t; - -typedef enum { - MAVLINK_TYPE_CHAR = 0, - MAVLINK_TYPE_UINT8_T = 1, - MAVLINK_TYPE_INT8_T = 2, - MAVLINK_TYPE_UINT16_T = 3, - MAVLINK_TYPE_INT16_T = 4, - MAVLINK_TYPE_UINT32_T = 5, - MAVLINK_TYPE_INT32_T = 6, - MAVLINK_TYPE_UINT64_T = 7, - MAVLINK_TYPE_INT64_T = 8, - MAVLINK_TYPE_FLOAT = 9, - MAVLINK_TYPE_DOUBLE = 10 -} mavlink_message_type_t; - -#define MAVLINK_MAX_FIELDS 64 - -typedef struct __mavlink_field_info { - const char *name; // name of this field - const char *print_format; // printing format hint, or NULL - mavlink_message_type_t type; // type of this field - unsigned int array_length; // if non-zero, field is an array - unsigned int wire_offset; // offset of each field in the payload - unsigned int structure_offset; // offset in a C structure -} mavlink_field_info_t; - -// note that in this structure the order of fields is the order -// in the XML file, not necessary the wire order -typedef struct __mavlink_message_info { - uint32_t msgid; // message ID - const char *name; // name of the message - unsigned num_fields; // how many fields in this message - mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information -} mavlink_message_info_t; - -#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) -#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) - -// checksum is immediately after the payload bytes -#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) -#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) - -typedef enum { - MAVLINK_COMM_0, - MAVLINK_COMM_1, - MAVLINK_COMM_2, - MAVLINK_COMM_3 -} mavlink_channel_t; - -/* - * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number - * of buffers they will use. If more are used, then the result will be - * a stack overrun - */ -#ifndef MAVLINK_COMM_NUM_BUFFERS -#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) -# define MAVLINK_COMM_NUM_BUFFERS 16 -#else -# define MAVLINK_COMM_NUM_BUFFERS 4 -#endif -#endif - -typedef enum { - MAVLINK_PARSE_STATE_UNINIT=0, - MAVLINK_PARSE_STATE_IDLE, - MAVLINK_PARSE_STATE_GOT_STX, - MAVLINK_PARSE_STATE_GOT_LENGTH, - MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS, - MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS, - MAVLINK_PARSE_STATE_GOT_SEQ, - MAVLINK_PARSE_STATE_GOT_SYSID, - MAVLINK_PARSE_STATE_GOT_COMPID, - MAVLINK_PARSE_STATE_GOT_MSGID1, - MAVLINK_PARSE_STATE_GOT_MSGID2, - MAVLINK_PARSE_STATE_GOT_MSGID3, - MAVLINK_PARSE_STATE_GOT_PAYLOAD, - MAVLINK_PARSE_STATE_GOT_CRC1, - MAVLINK_PARSE_STATE_GOT_BAD_CRC1, - MAVLINK_PARSE_STATE_SIGNATURE_WAIT -} mavlink_parse_state_t; ///< The state machine for the comm parser - -typedef enum { - MAVLINK_FRAMING_INCOMPLETE=0, - MAVLINK_FRAMING_OK=1, - MAVLINK_FRAMING_BAD_CRC=2, - MAVLINK_FRAMING_BAD_SIGNATURE=3 -} mavlink_framing_t; - -#define MAVLINK_STATUS_FLAG_IN_MAVLINK1 1 // last incoming packet was MAVLink1 -#define MAVLINK_STATUS_FLAG_OUT_MAVLINK1 2 // generate MAVLink1 by default -#define MAVLINK_STATUS_FLAG_IN_SIGNED 4 // last incoming packet was signed and validated -#define MAVLINK_STATUS_FLAG_IN_BADSIG 8 // last incoming packet had a bad signature - -#define MAVLINK_STX_MAVLINK1 0xFE // marker for old protocol - -typedef struct __mavlink_status { - uint8_t msg_received; ///< Number of received messages - uint8_t buffer_overrun; ///< Number of buffer overruns - uint8_t parse_error; ///< Number of parse errors - mavlink_parse_state_t parse_state; ///< Parsing state machine - uint8_t packet_idx; ///< Index in current packet - uint8_t current_rx_seq; ///< Sequence number of last packet received - uint8_t current_tx_seq; ///< Sequence number of last packet sent - uint16_t packet_rx_success_count; ///< Received packets - uint16_t packet_rx_drop_count; ///< Number of packet drops - uint8_t flags; ///< MAVLINK_STATUS_FLAG_* - uint8_t signature_wait; ///< number of signature bytes left to receive - struct __mavlink_signing *signing; ///< optional signing state - struct __mavlink_signing_streams *signing_streams; ///< global record of stream timestamps -} mavlink_status_t; - -/* - a callback function to allow for accepting unsigned packets - */ -typedef bool (*mavlink_accept_unsigned_t)(const mavlink_status_t *status, uint32_t msgid); - -/* - flags controlling signing - */ -#define MAVLINK_SIGNING_FLAG_SIGN_OUTGOING 1 - -/* - state of MAVLink signing for this channel - */ -typedef struct __mavlink_signing { - uint8_t flags; ///< MAVLINK_SIGNING_FLAG_* - uint8_t link_id; - uint64_t timestamp; - uint8_t secret_key[32]; - mavlink_accept_unsigned_t accept_unsigned_callback; -} mavlink_signing_t; - -/* - timestamp state of each logical signing stream. This needs to be the same structure for all - connections in order to be secure - */ -#ifndef MAVLINK_MAX_SIGNING_STREAMS -#define MAVLINK_MAX_SIGNING_STREAMS 16 -#endif -typedef struct __mavlink_signing_streams { - uint16_t num_signing_streams; - struct __mavlink_signing_stream { - uint8_t link_id; - uint8_t sysid; - uint8_t compid; - uint8_t timestamp_bytes[6]; - } stream[MAVLINK_MAX_SIGNING_STREAMS]; -} mavlink_signing_streams_t; - - -#define MAVLINK_BIG_ENDIAN 0 -#define MAVLINK_LITTLE_ENDIAN 1 - -#define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM 1 -#define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT 2 - -/* - entry in table of information about each message type - */ -typedef struct __mavlink_msg_entry { - uint32_t msgid; - uint8_t crc_extra; - uint8_t msg_len; - uint8_t flags; // MAV_MSG_ENTRY_FLAG_* - uint8_t target_system_ofs; // payload offset to target_system, or 0 - uint8_t target_component_ofs; // payload offset to target_component, or 0 -} mavlink_msg_entry_t; - -/* - incompat_flags bits - */ -#define MAVLINK_IFLAG_SIGNED 0x01 -#define MAVLINK_IFLAG_MASK 0x01 // mask of all understood bits - -#ifdef MAVLINK_USE_CXX_NAMESPACE -} // namespace mavlink -#endif diff --git a/include/mavlink/v2.0/message_definitions/common.xml b/include/mavlink/v2.0/message_definitions/common.xml deleted file mode 100644 index 26c9303..0000000 --- a/include/mavlink/v2.0/message_definitions/common.xml +++ /dev/null @@ -1,4130 +0,0 @@ - - - 3 - 0 - - - Micro air vehicle / autopilot classes. This identifies the individual model. - - Generic autopilot, full support for everything - - - Reserved for future use. - - - SLUGS autopilot, http://slugsuav.soe.ucsc.edu - - - ArduPilotMega / ArduCopter, http://diydrones.com - - - OpenPilot, http://openpilot.org - - - Generic autopilot only supporting simple waypoints - - - Generic autopilot supporting waypoints and other simple navigation commands - - - Generic autopilot supporting the full mission command set - - - No valid autopilot, e.g. a GCS or other MAVLink component - - - PPZ UAV - http://nongnu.org/paparazzi - - - UAV Dev Board - - - FlexiPilot - - - PX4 Autopilot - http://pixhawk.ethz.ch/px4/ - - - SMACCMPilot - http://smaccmpilot.org - - - AutoQuad -- http://autoquad.org - - - Armazila -- http://armazila.com - - - Aerob -- http://aerob.ru - - - ASLUAV autopilot -- http://www.asl.ethz.ch - - - SmartAP Autopilot - http://sky-drones.com - - - - - Generic micro air vehicle. - - - Fixed wing aircraft. - - - Quadrotor - - - Coaxial helicopter - - - Normal helicopter with tail rotor. - - - Ground installation - - - Operator control unit / ground control station - - - Airship, controlled - - - Free balloon, uncontrolled - - - Rocket - - - Ground rover - - - Surface vessel, boat, ship - - - Submarine - - - Hexarotor - - - Octorotor - - - Tricopter - - - Flapping wing - - - Kite - - - Onboard companion controller - - - Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. - - - Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. - - - Tiltrotor VTOL - - - - VTOL reserved 2 - - - VTOL reserved 3 - - - VTOL reserved 4 - - - VTOL reserved 5 - - - Onboard gimbal - - - Onboard ADSB peripheral - - - - These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. - - development release - - - alpha release - - - beta release - - - release candidate - - - official stable release - - - - - These flags encode the MAV mode. - - 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state. - - - 0b01000000 remote control input is enabled. - - - 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. - - - 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. - - - 0b00001000 guided mode enabled, system flies MISSIONs / mission items. - - - 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. - - - 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. - - - 0b00000001 Reserved for future use. - - - - These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. - - First bit: 10000000 - - - Second bit: 01000000 - - - Third bit: 00100000 - - - Fourth bit: 00010000 - - - Fifth bit: 00001000 - - - Sixt bit: 00000100 - - - Seventh bit: 00000010 - - - Eighth bit: 00000001 - - - - Override command, pauses current mission execution and moves immediately to a position - - Hold at the current position. - - - Continue with the next item in mission execution. - - - Hold at the current position of the system - - - Hold at the position specified in the parameters of the DO_HOLD action - - - - These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it - simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. - - System is not ready to fly, booting, calibrating, etc. No flag is set. - - - System is allowed to be active, under assisted RC control. - - - System is allowed to be active, under assisted RC control. - - - System is allowed to be active, under manual (RC) control, no stabilization - - - System is allowed to be active, under manual (RC) control, no stabilization - - - System is allowed to be active, under autonomous control, manual setpoint - - - System is allowed to be active, under autonomous control, manual setpoint - - - System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) - - - System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) - - - UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. - - - UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. - - - - - Uninitialized system, state is unknown. - - - System is booting up. - - - System is calibrating and not flight-ready. - - - System is grounded and on standby. It can be launched any time. - - - System is active and might be already airborne. Motors are engaged. - - - System is in a non-normal flight mode. It can however still navigate. - - - System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. - - - System just initialized its power-down sequence, will shut down now. - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - On Screen Display (OSD) devices for video links - - - Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - These encode the sensors whose status is sent as part of the SYS_STATUS message. - - 0x01 3D gyro - - - 0x02 3D accelerometer - - - 0x04 3D magnetometer - - - 0x08 absolute pressure - - - 0x10 differential pressure - - - 0x20 GPS - - - 0x40 optical flow - - - 0x80 computer vision position - - - 0x100 laser based position - - - 0x200 external ground truth (Vicon or Leica) - - - 0x400 3D angular rate control - - - 0x800 attitude stabilization - - - 0x1000 yaw position - - - 0x2000 z/altitude control - - - 0x4000 x/y position control - - - 0x8000 motor outputs / control - - - 0x10000 rc receiver - - - 0x20000 2nd 3D gyro - - - 0x40000 2nd 3D accelerometer - - - 0x80000 2nd 3D magnetometer - - - 0x100000 geofence - - - 0x200000 AHRS subsystem health - - - 0x400000 Terrain subsystem health - - - 0x800000 Motors are reversed - - - 0x1000000 Logging - - - 0x2000000 Battery - - - - - Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) - - - Local coordinate frame, Z-up (x: north, y: east, z: down). - - - NOT a coordinate frame, indicates a mission command. - - - Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. - - - Local coordinate frame, Z-down (x: east, y: north, z: up) - - - Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) - - - Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. - - - Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. - - - Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. - - - Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. - - - Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. - - - Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. - - - - - - - - - - - - - - - - - - - - - - - - - - Disable fenced mode - - - Switched to guided mode to return point (fence point 0) - - - Report fence breach, but don't take action - - - Switched to guided mode to return point (fence point 0) with manual throttle control - - - Switch to RTL (return to launch) mode and head for the return point. - - - - - No last fence breach - - - Breached minimum altitude - - - Breached maximum altitude - - - Breached fence boundary - - - - - Enumeration of possible mount operation modes - - Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization - - - Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. - - - Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization - - - Load neutral position and start RC Roll,Pitch,Yaw control with stabilization - - - Load neutral position and start to point to Lat,Lon,Alt - - - - Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. - - Navigate to MISSION. - Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) - Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached) - 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. - Desired yaw angle at MISSION (rotary wing). NaN for unchanged. - Latitude - Longitude - Altitude - - - 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 - - - Loiter around this MISSION for X turns - Turns - Empty - Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise - Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle - Latitude - Longitude - Altitude - - - Loiter around this MISSION for X seconds - Seconds (decimal) - Empty - Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise - Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle - Latitude - Longitude - Altitude - - - Return to launch location - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Land at location - Abort Alt - Empty - Empty - Desired yaw angle. NaN for unchanged. - Latitude - Longitude - Altitude - - - Takeoff from ground / hand - Minimum pitch (if airspeed sensor present), desired pitch without sensor - Empty - Empty - Yaw angle (if magnetometer present), ignored without magnetometer. NaN for unchanged. - Latitude - Longitude - Altitude - - - Land at local position (local frame only) - Landing target number (if available) - Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land - Landing descend rate [ms^-1] - Desired yaw angle [rad] - Y-axis position [m] - X-axis position [m] - Z-axis / ground level position [m] - - - Takeoff from local position (local frame only) - Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad] - Empty - Takeoff ascend rate [ms^-1] - Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these - Y-axis position [m] - X-axis position [m] - Z-axis position [m] - - - Vehicle following, i.e. this waypoint represents the position of a moving vehicle - Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation - Ground speed of vehicle to be followed - Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise - Desired yaw angle. - Latitude - Longitude - Altitude - - - Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. - Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. - Empty - Empty - Empty - Empty - Empty - Desired altitude in meters - - - Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. - Heading Required (0 = False) - Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter. - Empty - Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location - Latitude - Longitude - Altitude - - - Being following a target - System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode - RESERVED - RESERVED - altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home - altitude - RESERVED - TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout - - - Reposition the MAV after a follow target command has been sent - Camera q1 (where 0 is on the ray from the camera to the tracking device) - Camera q2 - Camera q3 - Camera q4 - altitude offset from target (m) - X offset from target (m) - Y offset from target (m) - - - 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 - - - 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 - - - Navigate to MISSION using a spline path. - Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) - Empty - Empty - Empty - Latitude/X of goal - Longitude/Y of goal - Altitude/Z of goal - - - Takeoff from ground using VTOL mode - Empty - Empty - Empty - Yaw angle in degrees. NaN for unchanged. - Latitude - Longitude - Altitude - - - Land using VTOL mode - Empty - Empty - Empty - Yaw angle in degrees. NaN for unchanged. - Latitude - Longitude - Altitude - - - - hand control over to an external controller - On / Off (> 0.5f on) - Empty - Empty - Empty - Empty - Empty - Empty - - - Delay the next navigation command a number of seconds or until a specified time - Delay in seconds (decimal, -1 to enable time-of-day fields) - hour (24h format, UTC, -1 to ignore) - minute (24h format, UTC, -1 to ignore) - second (24h format, UTC) - Empty - Empty - Empty - - - Descend and place payload. Vehicle descends until it detects a hanging payload has reached the ground, the gripper is opened to release the payload - Maximum distance to descend (meters) - Empty - Empty - Empty - Latitude (deg * 1E7) - Longitude (deg * 1E7) - Altitude (meters) - - - NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Delay mission state machine. - Delay in seconds (decimal) - Empty - Empty - Empty - Empty - Empty - Empty - - - Ascend/descend at rate. Delay mission state machine until desired altitude reached. - Descent / Ascend rate (m/s) - Empty - Empty - Empty - Empty - Empty - Finish Altitude - - - Delay mission state machine until within desired distance of next NAV point. - Distance (meters) - Empty - Empty - Empty - Empty - Empty - Empty - - - Reach a certain target angle. - target angle: [0-360], 0 is north - speed during yaw change:[deg per second] - direction: negative: counter clockwise, positive: clockwise [-1,1] - relative offset or absolute angle: [ 1,0] - Empty - Empty - Empty - - - NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Set system mode. - Mode, as defined by ENUM MAV_MODE - Custom mode - this is system specific, please refer to the individual autopilot specifications for details. - Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details. - Empty - Empty - Empty - Empty - - - Jump to the desired command in the mission list. Repeat this action only the specified number of times - Sequence number - Repeat count - Empty - Empty - Empty - Empty - Empty - - - Change speed and/or throttle set points. - Speed type (0=Airspeed, 1=Ground Speed) - Speed (m/s, -1 indicates no change) - Throttle ( Percent, -1 indicates no change) - absolute or relative [0,1] - Empty - Empty - Empty - - - Changes the home location either to the current location or a specified location. - Use current (1=use current location, 0=use specified location) - Empty - Empty - Empty - Latitude - Longitude - Altitude - - - Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. - Parameter number - Parameter value - Empty - Empty - Empty - Empty - Empty - - - Set a relay to a condition. - Relay number - Setting (1=on, 0=off, others possible depending on system hardware) - Empty - Empty - Empty - Empty - Empty - - - Cycle a relay on and off for a desired number of cyles with a desired period. - Relay number - Cycle count - Cycle time (seconds, decimal) - Empty - Empty - Empty - Empty - - - Set a servo to a desired PWM value. - Servo number - PWM (microseconds, 1000 to 2000 typical) - Empty - Empty - Empty - Empty - Empty - - - Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. - Servo number - PWM (microseconds, 1000 to 2000 typical) - Cycle count - Cycle time (seconds) - Empty - Empty - Empty - - - Terminate flight immediately - Flight termination activated if > 0.5 - Empty - Empty - Empty - Empty - Empty - Empty - - - Change altitude set point. - Altitude in meters - Mav frame of new altitude (see MAV_FRAME) - Empty - Empty - Empty - Empty - Empty - - - Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0 if not needed. If specified then it will be used to help find the closest landing sequence. - Empty - Empty - Empty - Empty - Latitude - Longitude - Empty - - - Mission command to perform a landing from a rally point. - Break altitude (meters) - Landing speed (m/s) - Empty - Empty - Empty - Empty - Empty - - - Mission command to safely abort an autonmous landing. - Altitude (meters) - Empty - Empty - Empty - Empty - Empty - Empty - - - Reposition the vehicle to a specific WGS84 global position. - Ground speed, less than 0 (-1) for default - Bitmask of option flags, see the MAV_DO_REPOSITION_FLAGS enum. - Reserved - Yaw heading, NaN for unchanged. For planes indicates loiter direction (0: clockwise, 1: counter clockwise) - Latitude (deg * 1E7) - Longitude (deg * 1E7) - Altitude (meters) - - - If in a GPS controlled position mode, hold the current position or continue. - 0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - Set moving direction to forward or reverse. - Direction (0=Forward, 1=Reverse) - Empty - Empty - Empty - Empty - Empty - Empty - - - Control onboard camera system. - Camera ID (-1 for all) - Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw - Transmission mode: 0: video stream, >0: single images every n seconds (decimal) - Recording: 0: disabled, 1: enabled compressed, 2: enabled raw - Empty - Empty - Empty - - - Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various 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 - - - - - Mission command to configure an on-board camera controller system. - Modes: P, TV, AV, M, Etc - Shutter speed: Divisor number for one second - Aperture: F stop number - ISO number e.g. 80, 100, 200, Etc - Exposure type enumerator - Command Identity - Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) - - - Mission command to control an on-board camera controller system. - Session control e.g. show/hide lens - Zoom's absolute position - Zooming step value to offset zoom from the current position - Focus Locking, Unlocking or Re-locking - Shooting Command - Command Identity - Test shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count. - - - - Mission command to configure a camera or antenna mount - Mount operation mode (see MAV_MOUNT_MODE enum) - stabilize roll? (1 = yes, 0 = no) - stabilize pitch? (1 = yes, 0 = no) - stabilize yaw? (1 = yes, 0 = no) - Empty - Empty - Empty - - - Mission command to control a camera or antenna mount - pitch (WIP: DEPRECATED: or lat in degrees) depending on mount mode. - roll (WIP: DEPRECATED: or lon in degrees) depending on mount mode. - yaw (WIP: DEPRECATED: or alt in meters) depending on mount mode. - WIP: alt in meters depending on mount mode. - WIP: latitude in degrees * 1E7, set if appropriate mount mode. - WIP: longitude in degrees * 1E7, set if appropriate mount mode. - MAV_MOUNT_MODE enum value - - - Mission command to set camera trigger distance for this flight. The camera is trigerred each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera. - Camera trigger distance (meters). -1 or 0 to ignore - Camera shutter integration time (milliseconds). -1 or 0 to ignore - Empty - Empty - Empty - Empty - Empty - - - Mission command to enable the geofence - enable? (0=disable, 1=enable, 2=disable_floor_only) - Empty - Empty - Empty - Empty - Empty - Empty - - - Mission command to trigger a parachute - action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.) - Empty - Empty - Empty - Empty - Empty - Empty - - - Mission command to perform motor test - motor sequence number (a number from 1 to max number of motors on the vehicle) - throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) - throttle - timeout (in seconds) - Empty - Empty - Empty - - - Change to/from inverted flight - inverted (0=normal, 1=inverted) - Empty - Empty - Empty - Empty - Empty - Empty - - - - Sets a desired vehicle turn angle and speed change - yaw angle to adjust steering by in centidegress - speed - normalized to 0 .. 1 - Empty - Empty - Empty - Empty - Empty - - - Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera. - Camera trigger cycle time (milliseconds). -1 or 0 to ignore. - Camera shutter integration time (milliseconds). Should be less than trigger cycle time. -1 or 0 to ignore. - Empty - Empty - Empty - Empty - Empty - - - Mission command to control a camera or antenna mount, using a quaternion as reference. - q1 - quaternion param #1, w (1 in null-rotation) - q2 - quaternion param #2, x (0 in null-rotation) - q3 - quaternion param #3, y (0 in null-rotation) - q4 - quaternion param #4, z (0 in null-rotation) - Empty - Empty - Empty - - - set id of master controller - System ID - Component ID - Empty - Empty - Empty - Empty - Empty - - - set limits for external control - timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout - absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit - absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit - horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit - Empty - Empty - Empty - - - Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines - 0: Stop engine, 1:Start Engine - 0: Warm start, 1:Cold start. Controls use of choke where applicable - Height delay (meters). This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay. - Empty - Empty - Empty - Empty - Empty - - - NOP - This command is only used to mark the upper limit of the DO commands in the enumeration - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero. - 1: gyro calibration, 3: gyro temperature calibration - 1: magnetometer calibration - 1: ground pressure calibration - 1: radio RC calibration, 2: RC trim calibration - 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration - 1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration - 1: ESC calibration, 3: barometer temperature calibration - - - Set sensor offsets. This command will be only accepted if in pre-flight mode. - Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometer - X axis offset (or generic dimension 1), in the sensor's raw units - Y axis offset (or generic dimension 2), in the sensor's raw units - Z axis offset (or generic dimension 3), in the sensor's raw units - Generic dimension 4, in the sensor's raw units - Generic dimension 5, in the sensor's raw units - Generic dimension 6, in the sensor's raw units - - - Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. - 1: Trigger actuator ID assignment and direction mapping. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. - Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults - Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults - Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging) - Reserved - Empty - Empty - Empty - - - Request the reboot or shutdown of system components. - 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded. - 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded. - WIP: 0: Do nothing for camera, 1: Reboot onboard camera, 2: Shutdown onboard camera, 3: Reboot onboard camera and keep it in the bootloader until upgraded - WIP: 0: Do nothing for mount (e.g. gimbal), 1: Reboot mount, 2: Shutdown mount, 3: Reboot mount and keep it in the bootloader until upgraded - Reserved, send 0 - Reserved, send 0 - WIP: ID (e.g. camera ID -1 for all IDs) - - - 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 - - - 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) - - - Arms / Disarms a component - 1 to arm, 0 to disarm - - - Request the home position from the vehicle. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - Starts receiver pairing - 0:Spektrum - 0:Spektrum DSM2, 1:Spektrum DSMX - - - Request the interval between messages for a particular MAVLink message ID - The MAVLink message ID - - - Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM - The MAVLink message ID - The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate. - - - Request MAVLink protocol version compatibility - 1: Request supported protocol versions by all nodes on the network - Reserved (all remaining params) - - - Request autopilot capabilities - 1: Request autopilot version - Reserved (all remaining params) - - - WIP: Request camera information (CAMERA_INFORMATION) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - 0: No action 1: Request camera capabilities - Reserved (all remaining params) - - - WIP: Request camera settings (CAMERA_SETTINGS) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - 0: No Action 1: Request camera settings - Reserved (all remaining params) - - - WIP: Set the camera settings part 1 (CAMERA_SETTINGS). Use NAN for values you don't want to change. - Camera ID (1 for first, 2 for second, etc.) - Aperture (1/value) - Shutter speed in seconds - ISO sensitivity - AE mode (Auto Exposure) (0: full auto 1: full manual 2: aperture priority 3: shutter priority) - EV value (when in auto exposure) - White balance (color temperature in K) (0: Auto WB) - - - WIP: Set the camera settings part 2 (CAMERA_SETTINGS). Use NAN for values you don't want to change. - Camera ID (1 for first, 2 for second, etc.) - Reserved for Flicker mode (0 for Auto) - Reserved for metering mode ID (Average, Center, Spot, etc.) - Reserved for image format ID (Jpeg/Raw/Jpeg+Raw) - Reserved for image quality ID (Compression) - Reserved for color mode ID (Neutral, Vivid, etc.) - Reserved - - - WIP: Request storage information (STORAGE_INFORMATION) - Storage ID (0 for all, 1 for first, 2 for second, etc.) - 0: No Action 1: Request storage information - Reserved (all remaining params) - - - WIP: Format a storage medium - Storage ID (1 for first, 2 for second, etc.) - 0: No action 1: Format storage - Reserved (all remaining params) - - - WIP: Request camera capture status (CAMERA_CAPTURE_STATUS) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - 0: No Action 1: Request camera capture status - Reserved (all remaining params) - - - WIP: Request flight information (FLIGHT_INFORMATION) - 1: Request flight information - Reserved (all remaining params) - - - WIP: Reset all camera settings to Factory Default (CAMERA_SETTINGS) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - 0: No Action 1: Reset all settings - Reserved (all remaining params) - - - WIP: Set camera running mode. Use NAN for values you don't want to change. - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Camera mode (0: photo mode, 1: video mode) - Audio recording enabled (0: off 1: on) - Reserved (all remaining params) - - - WIP: Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Duration between two consecutive pictures (in seconds) - Number of images to capture total - 0 for unlimited capture - Resolution horizontal in pixels (set to -1 for highest resolution possible) - Resolution vertical in pixels (set to -1 for highest resolution possible) - - - WIP: Stop image capture sequence - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Reserved - - - WIP: Re-request a CAMERA_IMAGE_CAPTURE packet - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Sequence number for missing CAMERA_IMAGE_CAPTURE packet - Reserved (all remaining params) - - - Enable or disable on-board camera triggering system. - Trigger enable/disable (0 for disable, 1 for start), -1 to ignore - 1 to reset the trigger sequence, -1 or 0 to ignore - 1 to pause triggering, but without switching the camera off or retracting it. -1 to ignore - - - WIP: Starts video capture (recording) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Frames per second, set to -1 for highest framerate possible. - Resolution horizontal in pixels (set to -1 for highest resolution possible) - Resolution vertical in pixels (set to -1 for highest resolution possible) - Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise time in Hz) - - - WIP: Stop the current video capture (recording) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Reserved - - - WIP: Start video streaming - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Reserved - - - WIP: Stop the current video streaming - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - Reserved - - - WIP: Request video stream information (VIDEO_STREAM_INFORMATION) - Camera ID (0 for all cameras, 1 for first, 2 for second, etc.) - 0: No Action 1: Request video stream information - Reserved (all remaining params) - - - Request to start streaming logging data over MAVLink (see also LOGGING_DATA message) - Format: 0: ULog - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - - - Request to stop streaming log data over MAVLink - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - - - - Landing gear ID (default: 0, -1 for all) - Landing gear position (Down: 0, Up: 1, NAN for no change) - Reserved, set to NAN - Reserved, set to NAN - Reserved, set to NAN - Reserved, set to NAN - Reserved, set to NAN - - - Create a panorama at the current position - Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle) - Viewing angle vertical of panorama (in degrees) - Speed of the horizontal rotation (in degrees per second) - Speed of the vertical rotation (in degrees per second) - - - Request VTOL transition - The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used. - - - This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocites along all three axes. - - - - This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position. - - Radius of desired circle in CIRCLE_MODE - User defined - User defined - User defined - Unscaled target latitude of center of circle in CIRCLE_MODE - Unscaled target longitude of center of circle in CIRCLE_MODE - - - Fence return point. There can only be one fence return point. - - Reserved - Reserved - Reserved - Reserved - Latitude - Longitude - Altitude - - - Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. - - Polygon vertex count - Reserved - Reserved - Reserved - Latitude - Longitude - Reserved - - - Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required. - - Polygon vertex count - Reserved - Reserved - Reserved - Latitude - Longitude - Reserved - - - Circular fence area. The vehicle must stay inside this area. - - radius in meters - Reserved - Reserved - Reserved - Latitude - Longitude - Reserved - - - Circular fence area. The vehicle must stay outside this area. - - radius in meters - Reserved - Reserved - Reserved - Latitude - Longitude - Reserved - - - Rally point. You can have multiple rally points defined. - - Reserved - Reserved - Reserved - Reserved - Latitude - Longitude - Altitude - - - - - Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. - Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list. - Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will. - Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will. - Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will. - Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT - Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT - Altitude, in meters AMSL - - - Control the payload deployment. - Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude, in meters AMSL - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - - - THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a - recommendation to the autopilot software. Individual autopilots may or may not obey - the recommended messages. - - Enable all data streams - - - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. - - - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS - - - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW - - - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. - - - Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. - - - Dependent on the autopilot - - - Dependent on the autopilot - - - Dependent on the autopilot - - - - The ROI (region of interest) for the vehicle. This can be - be used by the vehicle for camera/vehicle attitude alignment (see - MAV_CMD_NAV_ROI). - - No region of interest. - - - Point toward next MISSION. - - - Point toward given MISSION. - - - Point toward fixed location. - - - Point toward of given id. - - - - ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. - - Command / mission item is ok. - - - Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. - - - The system is refusing to accept this command from this source / communication partner. - - - Command or mission item is not supported, other commands would be accepted. - - - The coordinate frame of this command / mission item is not supported. - - - The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. - - - The X or latitude value is out of range. - - - The Y or longitude value is out of range. - - - The Z or altitude value is out of range. - - - - Specifies the datatype of a MAVLink parameter. - - 8-bit unsigned integer - - - 8-bit signed integer - - - 16-bit unsigned integer - - - 16-bit signed integer - - - 32-bit unsigned integer - - - 32-bit signed integer - - - 64-bit unsigned integer - - - 64-bit signed integer - - - 32-bit floating-point - - - 64-bit floating-point - - - - result from a mavlink command - - Command ACCEPTED and EXECUTED - - - Command TEMPORARY REJECTED/DENIED - - - Command PERMANENTLY DENIED - - - Command UNKNOWN/UNSUPPORTED - - - Command executed, but failed - - - WIP: Command being executed - - - - result in a mavlink mission ack - - mission accepted OK - - - generic error / not accepting mission commands at all right now - - - coordinate frame is not supported - - - command is not supported - - - mission item exceeds storage space - - - one of the parameters has an invalid value - - - param1 has an invalid value - - - param2 has an invalid value - - - param3 has an invalid value - - - param4 has an invalid value - - - x/param5 has an invalid value - - - y/param6 has an invalid value - - - param7 has an invalid value - - - received waypoint out of sequence - - - not accepting any mission commands from this communication partner - - - - Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. - - System is unusable. This is a "panic" condition. - - - Action should be taken immediately. Indicates error in non-critical systems. - - - Action must be taken immediately. Indicates failure in a primary system. - - - Indicates an error in secondary/redundant systems. - - - Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. - - - An unusual event has occured, though not an error condition. This should be investigated for the root cause. - - - Normal operational messages. Useful for logging. No action is required for these messages. - - - Useful non-operational messages that can assist in debugging. These should not occur during normal operation. - - - - Power supply status flags (bitmask) - - main brick power supply valid - - - main servo power supply valid for FMU - - - USB power is connected - - - peripheral supply is in over-current state - - - hi-power peripheral supply is in over-current state - - - Power status has changed since boot - - - - SERIAL_CONTROL device types - - First telemetry port - - - Second telemetry port - - - First GPS port - - - Second GPS port - - - system shell - - - - SERIAL_CONTROL flags (bitmask) - - Set if this is a reply - - - Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message - - - Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set - - - Block on writes to the serial port - - - Send multiple replies until port is drained - - - - Enumeration of distance sensor types - - Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units - - - Ultrasound rangefinder, e.g. MaxBotix units - - - Infrared rangefinder, e.g. Sharp units - - - - Enumeration of sensor orientation, according to its rotations - - Roll: 0, Pitch: 0, Yaw: 0 - - - Roll: 0, Pitch: 0, Yaw: 45 - - - Roll: 0, Pitch: 0, Yaw: 90 - - - Roll: 0, Pitch: 0, Yaw: 135 - - - Roll: 0, Pitch: 0, Yaw: 180 - - - Roll: 0, Pitch: 0, Yaw: 225 - - - Roll: 0, Pitch: 0, Yaw: 270 - - - Roll: 0, Pitch: 0, Yaw: 315 - - - Roll: 180, Pitch: 0, Yaw: 0 - - - Roll: 180, Pitch: 0, Yaw: 45 - - - Roll: 180, Pitch: 0, Yaw: 90 - - - Roll: 180, Pitch: 0, Yaw: 135 - - - Roll: 0, Pitch: 180, Yaw: 0 - - - Roll: 180, Pitch: 0, Yaw: 225 - - - Roll: 180, Pitch: 0, Yaw: 270 - - - Roll: 180, Pitch: 0, Yaw: 315 - - - Roll: 90, Pitch: 0, Yaw: 0 - - - Roll: 90, Pitch: 0, Yaw: 45 - - - Roll: 90, Pitch: 0, Yaw: 90 - - - Roll: 90, Pitch: 0, Yaw: 135 - - - Roll: 270, Pitch: 0, Yaw: 0 - - - Roll: 270, Pitch: 0, Yaw: 45 - - - Roll: 270, Pitch: 0, Yaw: 90 - - - Roll: 270, Pitch: 0, Yaw: 135 - - - Roll: 0, Pitch: 90, Yaw: 0 - - - Roll: 0, Pitch: 270, Yaw: 0 - - - Roll: 0, Pitch: 180, Yaw: 90 - - - Roll: 0, Pitch: 180, Yaw: 270 - - - Roll: 90, Pitch: 90, Yaw: 0 - - - Roll: 180, Pitch: 90, Yaw: 0 - - - Roll: 270, Pitch: 90, Yaw: 0 - - - Roll: 90, Pitch: 180, Yaw: 0 - - - Roll: 270, Pitch: 180, Yaw: 0 - - - Roll: 90, Pitch: 270, Yaw: 0 - - - Roll: 180, Pitch: 270, Yaw: 0 - - - Roll: 270, Pitch: 270, Yaw: 0 - - - Roll: 90, Pitch: 180, Yaw: 90 - - - Roll: 90, Pitch: 0, Yaw: 270 - - - Roll: 315, Pitch: 315, Yaw: 315 - - - - Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. - - Autopilot supports MISSION float message type. - - - Autopilot supports the new param float message type. - - - Autopilot supports MISSION_INT scaled integer message type. - - - Autopilot supports COMMAND_INT scaled integer message type. - - - Autopilot supports the new param union message type. - - - Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. - - - Autopilot supports commanding attitude offboard. - - - Autopilot supports commanding position and velocity targets in local NED frame. - - - Autopilot supports commanding position and velocity targets in global scaled integers. - - - Autopilot supports terrain protocol / data handling. - - - Autopilot supports direct actuator control. - - - Autopilot supports the flight termination command. - - - Autopilot supports onboard compass calibration. - - - Autopilot supports mavlink version 2. - - - Autopilot supports mission fence protocol. - - - Autopilot supports mission rally point protocol. - - - Autopilot supports the flight information protocol. - - - - Type of mission items being requested/sent in mission protocol. - - Items are mission commands for main mission. - - - Specifies GeoFence area(s). Items are MAV_CMD_FENCE_ GeoFence items. - - - Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_RALLY_POINT rally point items. - - - Only used in MISSION_CLEAR_ALL to clear all mission types. - - - - Enumeration of estimator types - - This is a naive estimator without any real covariance feedback. - - - Computer vision based estimate. Might be up to scale. - - - Visual-inertial estimate. - - - Plain GPS estimate. - - - Estimator integrating GPS and inertial sensing. - - - - Enumeration of battery types - - Not specified. - - - Lithium polymer battery - - - Lithium-iron-phosphate battery - - - Lithium-ION battery - - - Nickel metal hydride battery - - - - Enumeration of battery functions - - Battery function is unknown - - - Battery supports all flight systems - - - Battery for the propulsion system - - - Avionics battery - - - Payload battery - - - - Enumeration of VTOL states - - MAV is not configured as VTOL - - - VTOL is in transition from multicopter to fixed-wing - - - VTOL is in transition from fixed-wing to multicopter - - - VTOL is in multicopter state - - - VTOL is in fixed-wing state - - - - Enumeration of landed detector states - - MAV landed state is unknown - - - MAV is landed (on ground) - - - MAV is in air - - - MAV currently taking off - - - MAV currently landing - - - - Enumeration of the ADSB altimeter types - - Altitude reported from a Baro source using QNH reference - - - Altitude reported from a GNSS source - - - - ADSB classification for the type of vehicle emitting the transponder signal - - - - - - - - - - - - - - - - - - - - - - - These flags indicate status such as data validity of each data source. Set = data valid - - - - - - - - - - Bitmask of options for the MAV_CMD_DO_REPOSITION - - The aircraft should immediately transition into guided. This should not be set for follow me applications - - - - - Flags in EKF_STATUS message - - True if the attitude estimate is good - - - True if the horizontal velocity estimate is good - - - True if the vertical velocity estimate is good - - - True if the horizontal position (relative) estimate is good - - - True if the horizontal position (absolute) estimate is good - - - True if the vertical position (absolute) estimate is good - - - True if the vertical position (above ground) estimate is good - - - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) - - - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate - - - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate - - - True if the EKF has detected a GPS glitch - - - - - - throttle as a percentage from 0 ~ 100 - - - throttle as an absolute PWM value (normally in range of 1000~2000) - - - throttle pass-through from pilot's transmitter - - - - - - ignore altitude field - - - ignore hdop field - - - ignore vdop field - - - ignore horizontal velocity field (vn and ve) - - - ignore vertical velocity field (vd) - - - ignore speed accuracy field - - - ignore horizontal accuracy field - - - ignore vertical accuracy field - - - - Possible actions an aircraft can take to avoid a collision. - - Ignore any potential collisions - - - Report potential collision - - - Ascend or Descend to avoid threat - - - Move horizontally to avoid threat - - - Aircraft to move perpendicular to the collision's velocity vector - - - Aircraft to fly directly back to its launch point - - - Aircraft to stop in place - - - - Aircraft-rated danger from this threat. - - Not a threat - - - Craft is mildly concerned about this threat - - - Craft is panicing, and may take actions to avoid threat - - - - Source of information about this collision. - - ID field references ADSB_VEHICLE packets - - - ID field references MAVLink SRC ID - - - - Type of GPS fix - - No GPS connected - - - No position information, GPS is connected - - - 2D position - - - 3D position - - - DGPS/SBAS aided 3D position - - - RTK float, 3D position - - - RTK Fixed, 3D position - - - Static fixed, typically used for base stations - - - - - - The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). - Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - Autopilot type / class. defined in MAV_AUTOPILOT ENUM - System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - A bitfield for use for autopilot-specific flags. - System status flag, see MAV_STATE ENUM - MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version - - - The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. - Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - Battery voltage, in millivolts (1 = 1 millivolt) - Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - Autopilot-specific errors - Autopilot-specific errors - Autopilot-specific errors - Autopilot-specific errors - - - The system time is the time of the master clock, typically the computer clock of the main onboard computer. - Timestamp of the master clock in microseconds since UNIX epoch. - Timestamp of the component clock since boot time in milliseconds. - - - - A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. - Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) - PING sequence - 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - - - Request to control this MAV - System the GCS requests control for - 0: request control of this MAV, 1: Release control of this MAV - 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - - - Accept / deny control of this MAV - ID of the GCS this message - 0: request control of this MAV, 1: Release control of this MAV - 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - - - Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. - key - - - THIS INTERFACE IS DEPRECATED. USE COMMAND_LONG with MAV_CMD_DO_SET_MODE INSTEAD. Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. - The system setting the mode - The new base mode - The new autopilot-specific mode. This field can be ignored by an autopilot. - - - - Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. - System ID - Component ID - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - - - Request all parameters of this component. After this request, all parameters are emitted. - System ID - Component ID - - - Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Onboard parameter value - Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - Total number of onboard parameters - Index of this onboard parameter - - - Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. - System ID - Component ID - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Onboard parameter value - Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - - - The global position, as returned by the Global Positioning System (GPS). This is - NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - See the GPS_FIX_TYPE enum. - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. - GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - Number of satellites visible. If unknown, set to 255 - - - The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. - Number of satellites visible - Global satellite ID - 0: Satellite not used, 1: used for localization - Elevation (0: right on top of receiver, 90: on the horizon) of satellite - Direction of satellite, 0: 0 deg, 255: 360 deg. - Signal to noise ratio of satellite - - - The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units - Timestamp (milliseconds since system boot) - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - Angular speed around X axis (millirad /sec) - Angular speed around Y axis (millirad /sec) - Angular speed around Z axis (millirad /sec) - X Magnetic field (milli tesla) - Y Magnetic field (milli tesla) - Z Magnetic field (milli tesla) - - - The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - X acceleration (raw) - Y acceleration (raw) - Z acceleration (raw) - Angular speed around X axis (raw) - Angular speed around Y axis (raw) - Angular speed around Z axis (raw) - X Magnetic field (raw) - Y Magnetic field (raw) - Z Magnetic field (raw) - - - The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Absolute pressure (raw) - Differential pressure 1 (raw, 0 if nonexistant) - Differential pressure 2 (raw, 0 if nonexistant) - Raw Temperature measurement (raw) - - - The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. - Timestamp (milliseconds since system boot) - Absolute pressure (hectopascal) - Differential pressure 1 (hectopascal) - Temperature measurement (0.01 degrees celsius) - - - The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). - Timestamp (milliseconds since system boot) - Roll angle (rad, -pi..+pi) - Pitch angle (rad, -pi..+pi) - Yaw angle (rad, -pi..+pi) - Roll angular speed (rad/s) - Pitch angular speed (rad/s) - Yaw angular speed (rad/s) - - - The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). - Timestamp (milliseconds since system boot) - Quaternion component 1, w (1 in null-rotation) - Quaternion component 2, x (0 in null-rotation) - Quaternion component 3, y (0 in null-rotation) - Quaternion component 4, z (0 in null-rotation) - Roll angular speed (rad/s) - Pitch angular speed (rad/s) - Yaw angular speed (rad/s) - - - The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - Timestamp (milliseconds since system boot) - X Position - Y Position - Z Position - X Speed - Y Speed - Z Speed - - - The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It - is designed as scaled integer message since the resolution of float is not sufficient. - Timestamp (milliseconds since system boot) - Latitude, expressed as degrees * 1E7 - Longitude, expressed as degrees * 1E7 - Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) - Altitude above ground in meters, expressed as * 1000 (millimeters) - Ground X Speed (Latitude, positive north), expressed as m/s * 100 - Ground Y Speed (Longitude, positive east), expressed as m/s * 100 - Ground Z Speed (Altitude, positive down), expressed as m/s * 100 - Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - - - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX. - Timestamp (milliseconds since system boot) - Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - - - The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - Timestamp (milliseconds since system boot) - Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - - - The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. - Timestamp (microseconds since system boot) - Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - Servo output 1 value, in microseconds - Servo output 2 value, in microseconds - Servo output 3 value, in microseconds - Servo output 4 value, in microseconds - Servo output 5 value, in microseconds - Servo output 6 value, in microseconds - Servo output 7 value, in microseconds - Servo output 8 value, in microseconds - - Servo output 9 value, in microseconds - Servo output 10 value, in microseconds - Servo output 11 value, in microseconds - Servo output 12 value, in microseconds - Servo output 13 value, in microseconds - Servo output 14 value, in microseconds - Servo output 15 value, in microseconds - Servo output 16 value, in microseconds - - - Request a partial list of mission items from the system/component. http://qgroundcontrol.org/mavlink/waypoint_protocol. If start and end index are the same, just send one waypoint. - System ID - Component ID - Start index, 0 by default - End index, -1 by default (-1: send list to end). Else a valid index of the list - - Mission type, see MAV_MISSION_TYPE - - - This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED! - System ID - Component ID - Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - End index, equal or greater than start index. - - Mission type, see MAV_MISSION_TYPE - - - Message encoding a mission item. This message is emitted to announce - the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See also http://qgroundcontrol.org/mavlink/waypoint_protocol. - System ID - Component ID - Sequence - The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - false:0, true:1 - autocontinue to next wp - PARAM1, see MAV_CMD enum - PARAM2, see MAV_CMD enum - PARAM3, see MAV_CMD enum - PARAM4, see MAV_CMD enum - PARAM5 / local: x position, global: latitude - PARAM6 / y position: global: longitude - PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - - Mission type, see MAV_MISSION_TYPE - - - Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol - System ID - Component ID - Sequence - - Mission type, see MAV_MISSION_TYPE - - - Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between). - System ID - Component ID - Sequence - - - Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item. - Sequence - - - Request the overall list of mission items from the system/component. - System ID - Component ID - - Mission type, see MAV_MISSION_TYPE - - - This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs. - System ID - Component ID - Number of mission items in the sequence - - Mission type, see MAV_MISSION_TYPE - - - Delete all mission items at once. - System ID - Component ID - - Mission type, see MAV_MISSION_TYPE - - - A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION. - Sequence - - - Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). - System ID - Component ID - See MAV_MISSION_RESULT enum - - Mission type, see MAV_MISSION_TYPE - - - As local waypoints exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. - System ID - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84, in degrees * 1E7 - Altitude (AMSL), in meters * 1000 (positive for up) - - - Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (AMSL), in meters * 1000 (positive for up) - - - Bind a RC channel to a parameter. The parameter should change accoding to the RC channel value. - System ID - Component ID - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. - Initial parameter value - Scale, maps the RC range [-1, 1] to a parameter value - Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - - - Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. http://qgroundcontrol.org/mavlink/waypoint_protocol - System ID - Component ID - Sequence - - Mission type, see MAV_MISSION_TYPE - - - Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations. - System ID - Component ID - Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - x position 1 / Latitude 1 - y position 1 / Longitude 1 - z position 1 / Altitude 1 - x position 2 / Latitude 2 - y position 2 / Longitude 2 - z position 2 / Altitude 2 - - - Read out the safety zone the MAV currently assumes. - Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - x position 1 / Latitude 1 - y position 1 / Longitude 1 - z position 1 / Altitude 1 - x position 2 / Latitude 2 - y position 2 / Longitude 2 - z position 2 / Altitude 2 - - - The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). - Timestamp (microseconds since system boot or since UNIX epoch) - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - Roll angular speed (rad/s) - Pitch angular speed (rad/s) - Yaw angular speed (rad/s) - Attitude covariance - - - The state of the fixed wing navigation and position controller. - Current desired roll in degrees - Current desired pitch in degrees - Current desired heading in degrees - Bearing to current MISSION/target in degrees - Distance to active MISSION in meters - Current altitude error in meters - Current airspeed error in meters/second - Current crosstrack error on x-y plane in meters - - - The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset. - Timestamp (microseconds since system boot or since UNIX epoch) - Class id of the estimator this estimate originated from. - Latitude, expressed as degrees * 1E7 - Longitude, expressed as degrees * 1E7 - Altitude in meters, expressed as * 1000 (millimeters), above MSL - Altitude above ground in meters, expressed as * 1000 (millimeters) - Ground X Speed (Latitude), expressed as m/s - Ground Y Speed (Longitude), expressed as m/s - Ground Z Speed (Altitude), expressed as m/s - Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) - - - The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - Timestamp (microseconds since system boot or since UNIX epoch) - Class id of the estimator this estimate originated from. - X Position - Y Position - Z Position - X Speed (m/s) - Y Speed (m/s) - Z Speed (m/s) - X Acceleration (m/s^2) - Y Acceleration (m/s^2) - Z Acceleration (m/s^2) - Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) - - - The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - Timestamp (milliseconds since system boot) - Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - - - THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. - The target requested to send the message stream. - The target requested to send the message stream. - The ID of the requested data stream - The requested message rate - 1 to start sending, 0 to stop sending. - - - THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. - The ID of the requested data stream - The message rate - 1 stream is enabled, 0 stream is stopped. - - - This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled an buttons are also transmit as boolean values of their - The system to be controlled. - X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - - - The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16_MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - System ID - Component ID - RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - - - Message encoding a mission item. This message is emitted to announce - the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See alsohttp://qgroundcontrol.org/mavlink/waypoint_protocol. - System ID - Component ID - Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - false:0, true:1 - autocontinue to next wp - PARAM1, see MAV_CMD enum - PARAM2, see MAV_CMD enum - PARAM3, see MAV_CMD enum - PARAM4, see MAV_CMD enum - PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - - Mission type, see MAV_MISSION_TYPE - - - Metrics typically displayed on a HUD for fixed wing aircraft - Current airspeed in m/s - Current ground speed in m/s - Current heading in degrees, in compass units (0..360, 0=north) - Current throttle setting in integer percent, 0 to 100 - Current altitude (MSL), in meters - Current climb rate in meters/second - - - Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value. - System ID - Component ID - The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h - The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs - false:0, true:1 - autocontinue to next wp - PARAM1, see MAV_CMD enum - PARAM2, see MAV_CMD enum - PARAM3, see MAV_CMD enum - PARAM4, see MAV_CMD enum - PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - - - Send a command with up to seven parameters to the MAV - System which should execute the command - Component which should execute the command, 0 for all components - Command ID, as defined by MAV_CMD enum. - 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - Parameter 1, as defined by MAV_CMD enum. - Parameter 2, as defined by MAV_CMD enum. - Parameter 3, as defined by MAV_CMD enum. - Parameter 4, as defined by MAV_CMD enum. - Parameter 5, as defined by MAV_CMD enum. - Parameter 6, as defined by MAV_CMD enum. - Parameter 7, as defined by MAV_CMD enum. - - - Report status of a command. Includes feedback wether the command was executed. - Command ID, as defined by MAV_CMD enum. - See MAV_RESULT enum - - WIP: Needs to be set when MAV_RESULT is MAV_RESULT_IN_PROGRESS, values from 0 to 100 for progress percentage, 255 for unknown progress. - - - Setpoint in roll, pitch, yaw and thrust from the operator - Timestamp in milliseconds since system boot - Desired roll rate in radians per second - Desired pitch rate in radians per second - Desired yaw rate in radians per second - Collective thrust, normalized to 0 .. 1 - Flight mode switch position, 0.. 255 - Override mode switch position, 0.. 255 - - - Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system). - Timestamp in milliseconds since system boot - System ID - Component ID - Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude - Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - Body roll rate in radians per second - Body roll rate in radians per second - Body roll rate in radians per second - Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - - - Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way. - Timestamp in milliseconds since system boot - Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude - Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - Body roll rate in radians per second - Body pitch rate in radians per second - Body yaw rate in radians per second - Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - - - Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system). - Timestamp in milliseconds since system boot - System ID - Component ID - Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - X Position in NED frame in meters - Y Position in NED frame in meters - Z Position in NED frame in meters (note, altitude is negative in NED) - X velocity in NED frame in meter / s - Y velocity in NED frame in meter / s - Z velocity in NED frame in meter / s - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint in rad - yaw rate setpoint in rad/s - - - Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way. - Timestamp in milliseconds since system boot - Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - X Position in NED frame in meters - Y Position in NED frame in meters - Z Position in NED frame in meters (note, altitude is negative in NED) - X velocity in NED frame in meter / s - Y velocity in NED frame in meter / s - Z velocity in NED frame in meter / s - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint in rad - yaw rate setpoint in rad/s - - - Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system). - Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - System ID - Component ID - Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - X Position in WGS84 frame in 1e7 * meters - Y Position in WGS84 frame in 1e7 * meters - Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - X velocity in NED frame in meter / s - Y velocity in NED frame in meter / s - Z velocity in NED frame in meter / s - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint in rad - yaw rate setpoint in rad/s - - - Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way. - Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate - X Position in WGS84 frame in 1e7 * meters - Y Position in WGS84 frame in 1e7 * meters - Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT - X velocity in NED frame in meter / s - Y velocity in NED frame in meter / s - Z velocity in NED frame in meter / s - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint in rad - yaw rate setpoint in rad/s - - - The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - Timestamp (milliseconds since system boot) - X Position - Y Position - Z Position - Roll - Pitch - Yaw - - - DEPRECATED PACKET! Suffers from missing airspeed fields and singularities due to Euler angles. Please use HIL_STATE_QUATERNION instead. Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Roll angle (rad) - Pitch angle (rad) - Yaw angle (rad) - Body frame roll / phi angular speed (rad/s) - Body frame pitch / theta angular speed (rad/s) - Body frame yaw / psi angular speed (rad/s) - Latitude, expressed as * 1E7 - Longitude, expressed as * 1E7 - Altitude in meters, expressed as * 1000 (millimeters) - Ground X Speed (Latitude), expressed as m/s * 100 - Ground Y Speed (Longitude), expressed as m/s * 100 - Ground Z Speed (Altitude), expressed as m/s * 100 - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - - - Sent from autopilot to simulation. Hardware in the loop control outputs - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Control output -1 .. 1 - Control output -1 .. 1 - Control output -1 .. 1 - Throttle 0 .. 1 - Aux 1, -1 .. 1 - Aux 2, -1 .. 1 - Aux 3, -1 .. 1 - Aux 4, -1 .. 1 - System mode (MAV_MODE) - Navigation mode (MAV_NAV_MODE) - - - Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - RC channel 1 value, in microseconds - RC channel 2 value, in microseconds - RC channel 3 value, in microseconds - RC channel 4 value, in microseconds - RC channel 5 value, in microseconds - RC channel 6 value, in microseconds - RC channel 7 value, in microseconds - RC channel 8 value, in microseconds - RC channel 9 value, in microseconds - RC channel 10 value, in microseconds - RC channel 11 value, in microseconds - RC channel 12 value, in microseconds - Receive signal strength indicator, 0: 0%, 255: 100% - - - Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS) - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - System mode (MAV_MODE), includes arming state. - Flags as bitfield, reserved for future use. - - - Optical flow from a flow sensor (e.g. optical mouse sensor) - Timestamp (UNIX) - Sensor ID - Flow in pixels * 10 in x-sensor direction (dezi-pixels) - Flow in pixels * 10 in y-sensor direction (dezi-pixels) - Flow in meters in x-sensor direction, angular-speed compensated - Flow in meters in y-sensor direction, angular-speed compensated - Optical flow quality / confidence. 0: bad, 255: maximum quality - Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - - Flow rate in radians/second about X axis - Flow rate in radians/second about Y axis - - - Timestamp (microseconds, synced to UNIX time or since system boot) - Global X position - Global Y position - Global Z position - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - - - Timestamp (microseconds, synced to UNIX time or since system boot) - Global X position - Global Y position - Global Z position - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - - - Timestamp (microseconds, synced to UNIX time or since system boot) - Global X speed - Global Y speed - Global Z speed - - - Timestamp (microseconds, synced to UNIX time or since system boot) - Global X position - Global Y position - Global Z position - Roll angle in rad - Pitch angle in rad - Yaw angle in rad - - - The IMU readings in SI units in NED body frame - Timestamp (microseconds, synced to UNIX time or since system boot) - X acceleration (m/s^2) - Y acceleration (m/s^2) - Z acceleration (m/s^2) - Angular speed around X axis (rad / sec) - Angular speed around Y axis (rad / sec) - Angular speed around Z axis (rad / sec) - X Magnetic field (Gauss) - Y Magnetic field (Gauss) - Z Magnetic field (Gauss) - Absolute pressure in millibar - Differential pressure in millibar - Altitude calculated from pressure - Temperature in degrees celsius - Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - - - Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor) - Timestamp (microseconds, synced to UNIX time or since system boot) - Sensor ID - Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - RH rotation around X axis (rad) - RH rotation around Y axis (rad) - RH rotation around Z axis (rad) - Temperature * 100 in centi-degrees Celsius - Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - Time in microseconds since the distance was sampled. - Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - - - The IMU readings in SI units in NED body frame - Timestamp (microseconds, synced to UNIX time or since system boot) - X acceleration (m/s^2) - Y acceleration (m/s^2) - Z acceleration (m/s^2) - Angular speed around X axis in body frame (rad / sec) - Angular speed around Y axis in body frame (rad / sec) - Angular speed around Z axis in body frame (rad / sec) - X Magnetic field (Gauss) - Y Magnetic field (Gauss) - Z Magnetic field (Gauss) - Absolute pressure in millibar - Differential pressure (airspeed) in millibar - Altitude calculated from pressure - Temperature in degrees celsius - Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. - - - Status of simulation environment, if used - True attitude quaternion component 1, w (1 in null-rotation) - True attitude quaternion component 2, x (0 in null-rotation) - True attitude quaternion component 3, y (0 in null-rotation) - True attitude quaternion component 4, z (0 in null-rotation) - Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - X acceleration m/s/s - Y acceleration m/s/s - Z acceleration m/s/s - Angular speed around X axis rad/s - Angular speed around Y axis rad/s - Angular speed around Z axis rad/s - Latitude in degrees - Longitude in degrees - Altitude in meters - Horizontal position standard deviation - Vertical position standard deviation - True velocity in m/s in NORTH direction in earth-fixed NED frame - True velocity in m/s in EAST direction in earth-fixed NED frame - True velocity in m/s in DOWN direction in earth-fixed NED frame - - - Status generated by radio and injected into MAVLink stream. - Local signal strength - Remote signal strength - Remaining free buffer space in percent. - Background noise level - Remote background noise level - Receive errors - Count of error corrected packets - - - File transfer message - Network ID (0 for broadcast) - System ID (0 for broadcast) - Component ID (0 for broadcast) - Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - - - Time synchronization message. - Time sync timestamp 1 - Time sync timestamp 2 - - - Camera-IMU triggering and synchronisation message. - Timestamp for the image frame in microseconds - Image frame sequence - - - The global position, as returned by the Global Positioning System (GPS). This is - NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - GPS ground speed in cm/s. If unknown, set to: 65535 - GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - GPS velocity in cm/s in EAST direction in earth-fixed NED frame - GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - Number of satellites visible. If unknown, set to 255 - - - Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor) - Timestamp (microseconds, synced to UNIX time or since system boot) - Sensor ID - Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - RH rotation around X axis (rad) - RH rotation around Y axis (rad) - RH rotation around Z axis (rad) - Temperature * 100 in centi-degrees Celsius - Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - Time in microseconds since the distance was sampled. - Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. - - - Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations. - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - Body frame roll / phi angular speed (rad/s) - Body frame pitch / theta angular speed (rad/s) - Body frame yaw / psi angular speed (rad/s) - Latitude, expressed as * 1E7 - Longitude, expressed as * 1E7 - Altitude in meters, expressed as * 1000 (millimeters) - Ground X Speed (Latitude), expressed as cm/s - Ground Y Speed (Longitude), expressed as cm/s - Ground Z Speed (Altitude), expressed as cm/s - Indicated airspeed, expressed as cm/s - True airspeed, expressed as cm/s - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - - - The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units - Timestamp (milliseconds since system boot) - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - Angular speed around X axis (millirad /sec) - Angular speed around Y axis (millirad /sec) - Angular speed around Z axis (millirad /sec) - X Magnetic field (milli tesla) - Y Magnetic field (milli tesla) - Z Magnetic field (milli tesla) - - - Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. - System ID - Component ID - First log id (0 for first available) - Last log id (0xffff for last available) - - - Reply to LOG_REQUEST_LIST - Log id - Total number of logs - High log number - UTC timestamp of log in seconds since 1970, or 0 if not available - Size of the log (may be approximate) in bytes - - - Request a chunk of a log - System ID - Component ID - Log id (from LOG_ENTRY reply) - Offset into the log - Number of bytes - - - Reply to LOG_REQUEST_DATA - Log id (from LOG_ENTRY reply) - Offset into the log - Number of bytes (zero for end of log) - log data - - - Erase all logs - System ID - Component ID - - - Stop log transfer and resume normal logging - System ID - Component ID - - - data for injecting into the onboard GPS (used for DGPS) - System ID - Component ID - data length - raw data (110 is enough for 12 satellites of RTCMv2) - - - Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS frame). - Timestamp (microseconds since UNIX epoch or microseconds since system boot) - See the GPS_FIX_TYPE enum. - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) - GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - Number of satellites visible. If unknown, set to 255 - Number of DGPS satellites - Age of DGPS info - - - Power supply status - 5V rail voltage in millivolts - servo rail voltage in millivolts - power supply status flags (see MAV_POWER_STATUS enum) - - - Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate. - See SERIAL_CONTROL_DEV enum - See SERIAL_CONTROL_FLAG enum - Timeout for reply data in milliseconds - Baudrate of transfer. Zero means no change. - how many bytes in this transfer - serial data - - - RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting - Time since boot of last baseline message received in ms. - Identification of connected RTK receiver. - GPS Week Number of last baseline - GPS Time of Week of last baseline - GPS-specific health report for RTK data. - Rate of baseline messages being received by GPS, in HZ - Current number of sats used for RTK calculation. - Coordinate system of baseline. 0 == ECEF, 1 == NED - Current baseline in ECEF x or NED north component in mm. - Current baseline in ECEF y or NED east component in mm. - Current baseline in ECEF z or NED down component in mm. - Current estimate of baseline accuracy. - Current number of integer ambiguity hypotheses. - - - RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting - Time since boot of last baseline message received in ms. - Identification of connected RTK receiver. - GPS Week Number of last baseline - GPS Time of Week of last baseline - GPS-specific health report for RTK data. - Rate of baseline messages being received by GPS, in HZ - Current number of sats used for RTK calculation. - Coordinate system of baseline. 0 == ECEF, 1 == NED - Current baseline in ECEF x or NED north component in mm. - Current baseline in ECEF y or NED east component in mm. - Current baseline in ECEF z or NED down component in mm. - Current estimate of baseline accuracy. - Current number of integer ambiguity hypotheses. - - - The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units - Timestamp (milliseconds since system boot) - X acceleration (mg) - Y acceleration (mg) - Z acceleration (mg) - Angular speed around X axis (millirad /sec) - Angular speed around Y axis (millirad /sec) - Angular speed around Z axis (millirad /sec) - X Magnetic field (milli tesla) - Y Magnetic field (milli tesla) - Z Magnetic field (milli tesla) - - - type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - total data size in bytes (set on ACK only) - Width of a matrix or image - Height of a matrix or image - number of packets beeing sent (set on ACK only) - payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - JPEG quality out of [1,100] - - - sequence number (starting with 0 on every transmission) - image data bytes - - - Time since system boot - Minimum distance the sensor can measure in centimeters - Maximum distance the sensor can measure in centimeters - Current distance reading - Type from MAV_DISTANCE_SENSOR enum. - Onboard ID of the sensor - Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. - Measurement covariance in centimeters, 0 for unknown / invalid readings - - - Request for terrain data and terrain status - Latitude of SW corner of first grid (degrees *10^7) - Longitude of SW corner of first grid (in degrees *10^7) - Grid spacing in meters - Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - - - Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST - Latitude of SW corner of first grid (degrees *10^7) - Longitude of SW corner of first grid (in degrees *10^7) - Grid spacing in meters - bit within the terrain request mask - Terrain data in meters AMSL - - - Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission. - Latitude (degrees *10^7) - Longitude (degrees *10^7) - - - Response from a TERRAIN_CHECK request - Latitude (degrees *10^7) - Longitude (degrees *10^7) - grid spacing (zero if terrain at this location unavailable) - Terrain height in meters AMSL - Current vehicle height above lat/lon terrain height (meters) - Number of 4x4 terrain blocks waiting to be received or read from disk - Number of 4x4 terrain blocks in memory - - - Barometer readings for 2nd barometer - Timestamp (milliseconds since system boot) - Absolute pressure (hectopascal) - Differential pressure 1 (hectopascal) - Temperature measurement (0.01 degrees celsius) - - - Motion capture attitude and position - Timestamp (micros since boot or Unix epoch) - Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - X position in meters (NED) - Y position in meters (NED) - Z position in meters (NED) - - - Set the vehicle attitude and body angular rates. - Timestamp (micros since boot or Unix epoch) - Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - System ID - Component ID - Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - - - Set the vehicle attitude and body angular rates. - Timestamp (micros since boot or Unix epoch) - Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - - - The current system altitude. - Timestamp (micros since boot or Unix epoch) - This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. - This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - This is the altitude above the home position. It resets on each change of the current home position. - This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - - - The autopilot is requesting a resource (file, binary, other type of data) - Request ID. This ID should be re-used when sending back URI contents - The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - - - Barometer readings for 3rd barometer - Timestamp (milliseconds since system boot) - Absolute pressure (hectopascal) - Differential pressure 1 (hectopascal) - Temperature measurement (0.01 degrees celsius) - - - current motion information from a designated system - Timestamp in milliseconds since system boot - bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - AMSL, in meters - target velocity (0,0,0) for unknown - linear target acceleration (0,0,0) for unknown - (1 0 0 0 for unknown) - (0 0 0 for unknown) - eph epv - button states or switches of a tracker device - - - The smoothed, monotonic system state used to feed the control loops of the system. - Timestamp (micros since boot or Unix epoch) - X acceleration in body frame - Y acceleration in body frame - Z acceleration in body frame - X velocity in body frame - Y velocity in body frame - Z velocity in body frame - X position in local frame - Y position in local frame - Z position in local frame - Airspeed, set to -1 if unknown - Variance of body velocity estimate - Variance in local position - The attitude, represented as Quaternion - Angular rate in roll axis - Angular rate in pitch axis - Angular rate in yaw axis - - - Battery information - Battery ID - Function of the battery - Type (chemistry) of the battery - Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. - Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. - Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - Consumed energy, in HectoJoules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - - - Version and capability of autopilot software - bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) - Firmware version number - Middleware version number - Operating system version number - HW / board version (last 8 bytes should be silicon ID, if any) - Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - ID of the board vendor - ID of the product - UID if provided by hardware - - - The location of a landing area captured from a downward facing camera - Timestamp (micros since boot or Unix epoch) - The ID of the target if multiple targets are present - MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. - X-axis angular offset (in radians) of the target from the center of the image - Y-axis angular offset (in radians) of the target from the center of the image - Distance to the target from the vehicle in meters - Size in radians of target along x-axis - Size in radians of target along y-axis - - - - Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovaton test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovaton test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user. - Timestamp (micros since boot or Unix epoch) - Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. - Velocity innovation test ratio - Horizontal position innovation test ratio - Vertical position innovation test ratio - Magnetometer innovation test ratio - Height above terrain innovation test ratio - True airspeed innovation test ratio - Horizontal position 1-STD accuracy relative to the EKF local origin (m) - Vertical position 1-STD accuracy relative to the EKF local origin (m) - - - Timestamp (micros since boot or Unix epoch) - Wind in X (NED) direction in m/s - Wind in Y (NED) direction in m/s - Wind in Z (NED) direction in m/s - Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. - Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. - AMSL altitude (m) this measurement was taken at - Horizontal speed 1-STD accuracy - Vertical speed 1-STD accuracy - - - GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the sytem. - Timestamp (micros since boot or Unix epoch) - ID of the GPS for multiple GPS inputs - Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum). All other fields must be provided. - GPS time (milliseconds from start of GPS week) - GPS week number - 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84), in degrees * 1E7 - Altitude (AMSL, not WGS84), in m (positive for up) - GPS HDOP horizontal dilution of position in m - GPS VDOP vertical dilution of position in m - GPS velocity in m/s in NORTH direction in earth-fixed NED frame - GPS velocity in m/s in EAST direction in earth-fixed NED frame - GPS velocity in m/s in DOWN direction in earth-fixed NED frame - GPS speed accuracy in m/s - GPS horizontal accuracy in m - GPS vertical accuracy in m - Number of satellites visible. - - - RTCM message for injecting into the onboard GPS (used for DGPS) - LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - data length - RTCM message (may be fragmented) - - - Message appropriate for high latency connections like Iridium - System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h - A bitfield for use for autopilot-specific flags. - The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - roll (centidegrees) - pitch (centidegrees) - heading (centidegrees) - throttle (percentage) - heading setpoint (centidegrees) - Latitude, expressed as degrees * 1E7 - Longitude, expressed as degrees * 1E7 - Altitude above mean sea level (meters) - Altitude setpoint relative to the home position (meters) - airspeed (m/s) - airspeed setpoint (m/s) - groundspeed (m/s) - climb rate (m/s) - Number of satellites visible. If unknown, set to 255 - See the GPS_FIX_TYPE enum. - Remaining battery (percentage) - Autopilot temperature (degrees C) - Air temperature (degrees C) from airspeed sensor - failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - current waypoint number - distance to target (meters) - - - Vibration levels and accelerometer clipping - Timestamp (micros since boot or Unix epoch) - Vibration levels on X-axis - Vibration levels on Y-axis - Vibration levels on Z-axis - first accelerometer clipping count - second accelerometer clipping count - third accelerometer clipping count - - - This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The position the system will return to and land on. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84, in degrees * 1E7 - Altitude (AMSL), in meters * 1000 (positive for up) - Local X position of this position in the local coordinate frame - Local Y position of this position in the local coordinate frame - Local Z position of this position in the local coordinate frame - World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - - - The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. - System ID. - Latitude (WGS84), in degrees * 1E7 - Longitude (WGS84, in degrees * 1E7 - Altitude (AMSL), in meters * 1000 (positive for up) - Local X position of this position in the local coordinate frame - Local Y position of this position in the local coordinate frame - Local Z position of this position in the local coordinate frame - World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - - - This interface replaces DATA_STREAM - The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - - - Provides state for additional features - The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - - - The location and information of an ADSB vehicle - ICAO address - Latitude, expressed as degrees * 1E7 - Longitude, expressed as degrees * 1E7 - Type from ADSB_ALTITUDE_TYPE enum - Altitude(ASL) in millimeters - Course over ground in centidegrees - The horizontal velocity in centimeters/second - The vertical velocity in centimeters/second, positive is up - The callsign, 8+null - Type from ADSB_EMITTER_TYPE enum - Time since last communication in seconds - Flags to indicate various statuses including valid data fields - Squawk code - - - Information about a potential collision - Collision data source - Unique identifier, domain based on src field - Action that is being taken to avoid this collision - How concerned the aircraft is about this collision - Estimated time until collision occurs (seconds) - Closest vertical distance in meters between vehicle and object - Closest horizontal distance in meteres between vehicle and object - - - Message implementing parts of the V2 payload specs in V1 frames for transitional support. - Network ID (0 for broadcast) - System ID (0 for broadcast) - Component ID (0 for broadcast) - A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. - - - Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - Starting address of the debug variables - Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - Memory contents at specified address - - - Name - Timestamp - x - y - z - - - Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - Timestamp (milliseconds since system boot) - Name of the debug variable - Floating point value - - - Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - Timestamp (milliseconds since system boot) - Name of the debug variable - Signed integer value - - - Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). - Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - Status text message, without null termination character - - - Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. - Timestamp (milliseconds since system boot) - index of debug variable - DEBUG value - - - - Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing - system id of the target - component ID of the target - signing key - initial timestamp - - - Report button state change - Timestamp (milliseconds since system boot) - Time of last change of button state - Bitmap state of buttons - - - Control vehicle tone generation (buzzer) - System ID - Component ID - tune in board specific format - - - WIP: Information about a camera - Timestamp (milliseconds since system boot) - Camera ID (1 for first, 2 for second, etc.) - Number of cameras - Name of the camera vendor - Name of the camera model - Version of the camera firmware - Focal length in mm - Image sensor size horizontal in mm - Image sensor size vertical in mm - Image resolution in pixels horizontal - Image resolution in pixels vertical - Reserved for a lens ID - - - WIP: Settings of a camera, can be requested using MAV_CMD_REQUEST_CAMERA_SETTINGS and written using MAV_CMD_SET_CAMERA_SETTINGS - Timestamp (milliseconds since system boot) - Camera ID (1 for first, 2 for second, etc.) - 0: full auto 1: full manual 2: aperture priority 3: shutter priority - Aperture is 1/value - Shutter speed in seconds - ISO sensitivity - Exposure Value - Color temperature in degrees Kelvin. (0: Auto WB) - Reserved for a camera mode ID. (0: Photo 1: Video) - Audio recording enabled (0: off 1: on) - Reserved for a color mode ID (Neutral, Vivid, etc.) - Reserved for image format ID (Jpeg/Raw/Jpeg+Raw) - Reserved for image quality ID (Compression) - Reserved for metering mode ID (Average, Center, Spot, etc.) - Reserved for flicker mode ID (Auto, 60Hz, 50Hz, etc.) - - - WIP: Information about a storage medium - Timestamp (milliseconds since system boot) - Storage ID (1 for first, 2 for second, etc.) - Number of storage devices - Status of storage (0 not available, 1 unformatted, 2 formatted) - Total capacity in MiB - Used capacity in MiB - Available capacity in MiB - Read speed in MiB/s - Write speed in MiB/s - - - WIP: Information about the status of a capture - Timestamp (milliseconds since system boot) - Camera ID (1 for first, 2 for second, etc.) - Current status of image capturing (0: not running, 1: interval capture in progress) - Current status of video capturing (0: not running, 1: capture in progress) - Image capture interval in seconds - Video frame rate in Hz - Image resolution in pixels horizontal - Image resolution in pixels vertical - Video resolution in pixels horizontal - Video resolution in pixels vertical - Time in milliseconds since recording started - Available storage capacity in MiB - - - WIP: Information about a captured image - Timestamp (milliseconds since system boot) - Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. - Camera ID (1 for first, 2 for second, etc.) - Latitude, expressed as degrees * 1E7 where image was taken - Longitude, expressed as degrees * 1E7 where capture was taken - Altitude in meters, expressed as * 1E3 (AMSL, not WGS84) where image was taken - Altitude above ground in meters, expressed as * 1E3 where image was taken - Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0) - Zero based index of this image (image count since armed -1) - Boolean indicating success (1) or failure (0) while capturing this image. - URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. - - - WIP: Information about flight since last arming - Timestamp (milliseconds since system boot) - Timestamp at arming (microseconds since UNIX epoch) in UTC, 0 for unknown - Timestamp at takeoff (microseconds since UNIX epoch) in UTC, 0 for unknown - Universally unique identifier (UUID) of flight, should correspond to name of logfiles - - - WIP: Orientation of a mount - Timestamp (milliseconds since system boot) - Roll in degrees - Pitch in degrees - Yaw in degrees - - - A message containing logged data (see also MAV_CMD_LOGGING_START) - system ID of the target - component ID of the target - sequence number (can wrap) - data length - offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - logged data - - - A message containing logged data which requires a LOGGING_ACK to be sent back - system ID of the target - component ID of the target - sequence number (can wrap) - data length - offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists). - logged data - - - An ack for a LOGGING_DATA_ACKED message - system ID of the target - component ID of the target - sequence number (must match the one in LOGGING_DATA_ACKED) - - - WIP: Information about video stream - Camera ID (1 for first, 2 for second, etc.) - Current status of video streaming (0: not running, 1: in progress) - Frames per second - Resolution horizontal in pixels - Resolution vertical in pixels - Bit rate in bits per second - Video image rotation clockwise - Video stream URI - - - WIP: Message that sets video stream settings - system ID of the target - component ID of the target - Camera ID (1 for first, 2 for second, etc.) - Frames per second (set to -1 for highest framerate possible) - Resolution horizontal in pixels (set to -1 for highest resolution possible) - Resolution vertical in pixels (set to -1 for highest resolution possible) - Bit rate in bits per second (set to -1 for auto) - Video image rotation clockwise (0-359 degrees) - Video stream URI - - - WIP: Version and capability of protocol version. This message is the response to REQUEST_PROTOCOL_VERSION and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to REQUEST_PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly. - Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. - Minimum MAVLink version supported - Maximum MAVLink version supported (set to the same value as version by default) - The first 8 bytes (not characters printed in hex!) of the git hash. - The first 8 bytes (not characters printed in hex!) of the git hash. - - - diff --git a/include/mavlink/v2.0/protocol.h b/include/mavlink/v2.0/protocol.h deleted file mode 100644 index 20d218f..0000000 --- a/include/mavlink/v2.0/protocol.h +++ /dev/null @@ -1,334 +0,0 @@ -#pragma once - -#include "string.h" -#include "mavlink_types.h" - -/* - If you want MAVLink on a system that is native big-endian, - you need to define NATIVE_BIG_ENDIAN -*/ -#ifdef NATIVE_BIG_ENDIAN -# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN) -#else -# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) -#endif - -#ifndef MAVLINK_STACK_BUFFER -#define MAVLINK_STACK_BUFFER 0 -#endif - -#ifndef MAVLINK_AVOID_GCC_STACK_BUG -# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) -#endif - -#ifndef MAVLINK_ASSERT -#define MAVLINK_ASSERT(x) -#endif - -#ifndef MAVLINK_START_UART_SEND -#define MAVLINK_START_UART_SEND(chan, length) -#endif - -#ifndef MAVLINK_END_UART_SEND -#define MAVLINK_END_UART_SEND(chan, length) -#endif - -/* option to provide alternative implementation of mavlink_helpers.h */ -#ifdef MAVLINK_SEPARATE_HELPERS - - #define MAVLINK_HELPER - - /* decls in sync with those in mavlink_helpers.h */ - #ifndef MAVLINK_GET_CHANNEL_STATUS - MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan); - #endif - MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan); - MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra); - MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t min_length, uint8_t length, uint8_t crc_extra); - #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint32_t msgid, const char *packet, - uint8_t min_length, uint8_t length, uint8_t crc_extra); - #endif - 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); - MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c); - MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, - mavlink_status_t* status, - uint8_t c, - mavlink_message_t* r_message, - mavlink_status_t* r_mavlink_status); - MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); - MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); - MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, - uint8_t* r_bit_index, uint8_t* buffer); - MAVLINK_HELPER const mavlink_msg_entry_t *mavlink_get_msg_entry(uint32_t msgid); - #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); - MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg); - #endif - -#else - - #define MAVLINK_HELPER static inline - #include "mavlink_helpers.h" - -#endif // MAVLINK_SEPARATE_HELPERS - - -/** - * @brief Get the required buffer size for this message - */ -static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) -{ - if (msg->magic == MAVLINK_STX_MAVLINK1) { - return msg->len + MAVLINK_CORE_HEADER_MAVLINK1_LEN+1 + 2; - } - uint16_t signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0; - return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES + signature_len; -} - -#if MAVLINK_NEED_BYTE_SWAP -static inline void byte_swap_2(char *dst, const char *src) -{ - dst[0] = src[1]; - dst[1] = src[0]; -} -static inline void byte_swap_4(char *dst, const char *src) -{ - dst[0] = src[3]; - dst[1] = src[2]; - dst[2] = src[1]; - dst[3] = src[0]; -} -static inline void byte_swap_8(char *dst, const char *src) -{ - dst[0] = src[7]; - dst[1] = src[6]; - dst[2] = src[5]; - dst[3] = src[4]; - dst[4] = src[3]; - dst[5] = src[2]; - dst[6] = src[1]; - dst[7] = src[0]; -} -#elif !MAVLINK_ALIGNED_FIELDS -static inline void byte_copy_2(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; -} -static inline void byte_copy_4(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; - dst[2] = src[2]; - dst[3] = src[3]; -} -static inline void byte_copy_8(char *dst, const char *src) -{ - memcpy(dst, src, 8); -} -#endif - -#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b -#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b -#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b - -#if MAVLINK_NEED_BYTE_SWAP -#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#elif !MAVLINK_ALIGNED_FIELDS -#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#else -#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b -#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b -#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b -#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b -#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b -#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b -#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b -#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b -#endif - -/* - like memcpy(), but if src is NULL, do a memset to zero -*/ -static inline void mav_array_memcpy(void *dest, const void *src, size_t n) -{ - if (src == NULL) { - memset(dest, 0, n); - } else { - memcpy(dest, src, n); - } -} - -/* - * Place a char array into a buffer - */ -static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -/* - * Place a uint8_t array into a buffer - */ -static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -/* - * Place a int8_t array into a buffer - */ -static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -#if MAVLINK_NEED_BYTE_SWAP -#define _MAV_PUT_ARRAY(TYPE, V) \ -static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ -{ \ - if (b == NULL) { \ - memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ - } else { \ - uint16_t i; \ - for (i=0; imsgid) { - - case MAVLINK_MSG_ID_GA_PAYLOAD_FEEDBACK: - decode_msg_ga_payload_feedback(msg, busInfo, yvec0, OFFSET_GA_PAYLOAD_FEEDBACK); - break; - - case MAVLINK_MSG_ID_GA_PAYLOAD_COMMANDS: - decode_msg_ga_payload_commands(msg, busInfo, yvec1, OFFSET_GA_PAYLOAD_COMMANDS); - break; - - case MAVLINK_MSG_ID_DATA96: - decode_msg_data96(msg, busInfo, yvec2, OFFSET_DATA96); - break; - - case MAVLINK_MSG_ID_HEARTBEAT: - decode_msg_heartbeat(msg, busInfo, yvec3, OFFSET_HEARTBEAT); - break; - } -} diff --git a/include/sfun_mavlink_msg_attitude.h b/include/sfun_mavlink_msg_attitude.h deleted file mode 100644 index 015e123..0000000 --- a/include/sfun_mavlink_msg_attitude.h +++ /dev/null @@ -1,85 +0,0 @@ -/* -DO NOT EDIT. -This file was automatically created by the Matlab function 'create_sfun_header' on 05-Dec-2017 13:24:43 -as part of Simulink MAVLink library. -*/ - -#include "D:\simulink_mavlink\include\mavlink\v1.0\common\mavlink_msg_attitude.h" -#define BUS_NAME_ATTITUDE "mavlink_attitude_t" -#define NFIELDS_BUS_ATTITUDE 7 -#define ENCODED_LEN_ATTITUDE (MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_ATTITUDE_LEN) - -/* -Encode the busInfo vector. This vector stores the starting index and total offset -for every element of the message bus. This is the standard way Simulink s-functions -handle bus interfaces. -*/ -static inline void encode_businfo_attitude(SimStruct *S, int_T *busInfo, const int_T offset) -{ - slDataTypeAccess *dta = ssGetDataTypeAccess(S); - const char *bpath = ssGetPath(S); - DTypeId BUSId = ssGetDataTypeId(S, BUS_NAME_ATTITUDE); - - busInfo[offset+0] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 0); - busInfo[offset+1] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "uint32")); - busInfo[offset+2] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 1); - busInfo[offset+3] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "single")); - busInfo[offset+4] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 2); - busInfo[offset+5] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "single")); - busInfo[offset+6] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 3); - busInfo[offset+7] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "single")); - busInfo[offset+8] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 4); - busInfo[offset+9] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "single")); - busInfo[offset+10] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 5); - busInfo[offset+11] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "single")); - busInfo[offset+12] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 6); - busInfo[offset+13] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "single")); - ssSetUserData(S, busInfo); -} - - -/* -Encode the incoming character vector into the MAVLink bitstream. This process -consists of two stages - encode this character vector into a bus (using the -busInfo vector), and pass this struct to the MAVLink library to encode it into -a bitstream. -*/ -static inline uint16_t encode_vector_attitude(const char *uvec, const int_T *busInfo, uint8_T *yvec, const int_T offset) -{ - mavlink_attitude_t ubus; - mavlink_message_t msg_encoded; - - - (void) memcpy(&ubus.time_boot_ms, uvec + busInfo[offset+0], busInfo[offset+1]); - (void) memcpy(&ubus.roll, uvec + busInfo[offset+2], busInfo[offset+3]); - (void) memcpy(&ubus.pitch, uvec + busInfo[offset+4], busInfo[offset+5]); - (void) memcpy(&ubus.yaw, uvec + busInfo[offset+6], busInfo[offset+7]); - (void) memcpy(&ubus.rollspeed, uvec + busInfo[offset+8], busInfo[offset+9]); - (void) memcpy(&ubus.pitchspeed, uvec + busInfo[offset+10], busInfo[offset+11]); - (void) memcpy(&ubus.yawspeed, uvec + busInfo[offset+12], busInfo[offset+13]); - - mavlink_msg_attitude_encode(SYS_ID, COMP_ID, &msg_encoded, &ubus); - return mavlink_msg_to_send_buffer(yvec, &msg_encoded); -} - - -/* -Decode the incoming MAVLink message into an output character vector. This process -consists of two stages - use the MAVLink library to convert the MAVLink message -into its appropriate struct, and then decode this struct into the output character -vector according to busInfo. -*/ -static inline void decode_msg_attitude(const mavlink_message_t* msg_encoded, const int_T *busInfo, char *yvec, const int_T offset) -{ - mavlink_attitude_t ybus; - mavlink_msg_attitude_decode(msg_encoded, &ybus); - - - (void) memcpy(yvec + busInfo[offset+0], &ybus.time_boot_ms, busInfo[offset+1]); - (void) memcpy(yvec + busInfo[offset+2], &ybus.roll, busInfo[offset+3]); - (void) memcpy(yvec + busInfo[offset+4], &ybus.pitch, busInfo[offset+5]); - (void) memcpy(yvec + busInfo[offset+6], &ybus.yaw, busInfo[offset+7]); - (void) memcpy(yvec + busInfo[offset+8], &ybus.rollspeed, busInfo[offset+9]); - (void) memcpy(yvec + busInfo[offset+10], &ybus.pitchspeed, busInfo[offset+11]); - (void) memcpy(yvec + busInfo[offset+12], &ybus.yawspeed, busInfo[offset+13]); -} diff --git a/include/sfun_mavlink_msg_raw_imu.h b/include/sfun_mavlink_msg_raw_imu.h deleted file mode 100644 index f577a6f..0000000 --- a/include/sfun_mavlink_msg_raw_imu.h +++ /dev/null @@ -1,100 +0,0 @@ -/* -DO NOT EDIT. -This file was automatically created by the Matlab function 'create_sfun_header' on 05-Dec-2017 13:24:43 -as part of Simulink MAVLink library. -*/ - -#include "D:\simulink_mavlink\include\mavlink\v1.0\common\mavlink_msg_raw_imu.h" -#define BUS_NAME_RAW_IMU "mavlink_raw_imu_t" -#define NFIELDS_BUS_RAW_IMU 10 -#define ENCODED_LEN_RAW_IMU (MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_RAW_IMU_LEN) - -/* -Encode the busInfo vector. This vector stores the starting index and total offset -for every element of the message bus. This is the standard way Simulink s-functions -handle bus interfaces. -*/ -static inline void encode_businfo_raw_imu(SimStruct *S, int_T *busInfo, const int_T offset) -{ - slDataTypeAccess *dta = ssGetDataTypeAccess(S); - const char *bpath = ssGetPath(S); - DTypeId BUSId = ssGetDataTypeId(S, BUS_NAME_RAW_IMU); - - busInfo[offset+0] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 0); - busInfo[offset+1] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "double")); - busInfo[offset+2] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 1); - busInfo[offset+3] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "int16")); - busInfo[offset+4] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 2); - busInfo[offset+5] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "int16")); - busInfo[offset+6] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 3); - busInfo[offset+7] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "int16")); - busInfo[offset+8] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 4); - busInfo[offset+9] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "int16")); - busInfo[offset+10] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 5); - busInfo[offset+11] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "int16")); - busInfo[offset+12] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 6); - busInfo[offset+13] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "int16")); - busInfo[offset+14] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 7); - busInfo[offset+15] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "int16")); - busInfo[offset+16] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 8); - busInfo[offset+17] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "int16")); - busInfo[offset+18] = dtaGetDataTypeElementOffset(dta, bpath, BUSId, 9); - busInfo[offset+19] = dtaGetDataTypeSize(dta, bpath, ssGetDataTypeId(S, "int16")); - ssSetUserData(S, busInfo); -} - - -/* -Encode the incoming character vector into the MAVLink bitstream. This process -consists of two stages - encode this character vector into a bus (using the -busInfo vector), and pass this struct to the MAVLink library to encode it into -a bitstream. -*/ -static inline uint16_t encode_vector_raw_imu(const char *uvec, const int_T *busInfo, uint8_T *yvec, const int_T offset) -{ - mavlink_raw_imu_t ubus; - mavlink_message_t msg_encoded; - - double time_usec; - - (void) memcpy(&time_usec, uvec + busInfo[offset+0], busInfo[offset+1]); - ubus.time_usec = (uint64_t) time_usec; - (void) memcpy(&ubus.xacc, uvec + busInfo[offset+2], busInfo[offset+3]); - (void) memcpy(&ubus.yacc, uvec + busInfo[offset+4], busInfo[offset+5]); - (void) memcpy(&ubus.zacc, uvec + busInfo[offset+6], busInfo[offset+7]); - (void) memcpy(&ubus.xgyro, uvec + busInfo[offset+8], busInfo[offset+9]); - (void) memcpy(&ubus.ygyro, uvec + busInfo[offset+10], busInfo[offset+11]); - (void) memcpy(&ubus.zgyro, uvec + busInfo[offset+12], busInfo[offset+13]); - (void) memcpy(&ubus.xmag, uvec + busInfo[offset+14], busInfo[offset+15]); - (void) memcpy(&ubus.ymag, uvec + busInfo[offset+16], busInfo[offset+17]); - (void) memcpy(&ubus.zmag, uvec + busInfo[offset+18], busInfo[offset+19]); - - mavlink_msg_raw_imu_encode(SYS_ID, COMP_ID, &msg_encoded, &ubus); - return mavlink_msg_to_send_buffer(yvec, &msg_encoded); -} - - -/* -Decode the incoming MAVLink message into an output character vector. This process -consists of two stages - use the MAVLink library to convert the MAVLink message -into its appropriate struct, and then decode this struct into the output character -vector according to busInfo. -*/ -static inline void decode_msg_raw_imu(const mavlink_message_t* msg_encoded, const int_T *busInfo, char *yvec, const int_T offset) -{ - mavlink_raw_imu_t ybus; - mavlink_msg_raw_imu_decode(msg_encoded, &ybus); - - double time_usec = (double) ybus.time_usec; - - (void) memcpy(yvec + busInfo[offset+0], &time_usec, busInfo[offset+1]); - (void) memcpy(yvec + busInfo[offset+2], &ybus.xacc, busInfo[offset+3]); - (void) memcpy(yvec + busInfo[offset+4], &ybus.yacc, busInfo[offset+5]); - (void) memcpy(yvec + busInfo[offset+6], &ybus.zacc, busInfo[offset+7]); - (void) memcpy(yvec + busInfo[offset+8], &ybus.xgyro, busInfo[offset+9]); - (void) memcpy(yvec + busInfo[offset+10], &ybus.ygyro, busInfo[offset+11]); - (void) memcpy(yvec + busInfo[offset+12], &ybus.zgyro, busInfo[offset+13]); - (void) memcpy(yvec + busInfo[offset+14], &ybus.xmag, busInfo[offset+15]); - (void) memcpy(yvec + busInfo[offset+16], &ybus.ymag, busInfo[offset+17]); - (void) memcpy(yvec + busInfo[offset+18], &ybus.zmag, busInfo[offset+19]); -} diff --git a/setup.m b/setup.m new file mode 100644 index 0000000..ea69fa6 --- /dev/null +++ b/setup.m @@ -0,0 +1,45 @@ +% Example set up file for creating the Simulink models for exchanging +% MAVLink messages with PX4 according to the Simulator MAVLink API: +% https://dev.px4.io/master/en/simulation/index.html + +% In this example, a single message, attitude, is sent from one port from +% Simulink and received and decoded on another port. This process tests +% that the MAVLink encoding/decoding works correctly. You can then change +% the options below to include whichever messages need to be +% encoded/decoded for your application. + + +%% Set up paths and configuration options + +addpath(genpath(cd)); + +% Full path to the directory where MAVLink messages are located +% (DO NOT use relative path) +mavlink_path = '/Users/aditya/Documents/PX4/mavlink/include/mavlink/v2.0/common'; + + +% Select messages to send +messages_to_send = { + 'attitude'; + }; + +% Select messages to receive +messages_to_receive = { + 'attitude'; + }; + + +%% Write and compile S-Functions + +% Individual encoders for each message to send +for i = 1:length(messages_to_send) + filename = strcat(mavlink_path, '/mavlink_msg_', messages_to_send{i}, '.h'); + create_sfun_encode(filename); +end + +% Single decoder for all received messages +filenames = cell(size(messages_to_receive)); +for i = 1:length(messages_to_receive) + filenames{i} = strcat(mavlink_path, '/mavlink_msg_', messages_to_receive{i}, '.h'); +end +create_sfun_decode(filenames); diff --git a/sfunctions/sfun_decode_mavlink.cpp b/sfunctions/sfun_decode_mavlink.cpp deleted file mode 100644 index 173a4c0..0000000 --- a/sfunctions/sfun_decode_mavlink.cpp +++ /dev/null @@ -1,190 +0,0 @@ -/* -DO NOT EDIT. -This file was automatically created by the Matlab function 'create_sfun_decode' on 03-Feb-2018 14:21:39 -as part of Simulink MAVLink library. -*/ - -#define S_FUNCTION_NAME sfun_decode_mavlink -#define S_FUNCTION_LEVEL 2 - -#include "simstruc.h" - -// System and Component IDs for MAVLink communication -#define SYS_ID 100 -#define COMP_ID 200 - -#include "D:\simulink_mavlink\include\mavlink\v2.0\ardupilotmega\mavlink.h" - -#include "D:\simulink_mavlink\include\sfun_decode_mavlink.h" - -/* Function: mdlInitializeSizes ================================================ - * REQUIRED METHOD - * Abstract: - * The sizes information is used by Simulink to determine the S-function - * block's characteristics (number of inputs, outputs, states, etc.). - */ -static void mdlInitializeSizes(SimStruct *S) -{ - - DECL_AND_INIT_DIMSINFO(inputDimsInfo); - DECL_AND_INIT_DIMSINFO(outputDimsInfo); - - ssSetNumSFcnParams(S, 0); - if (ssGetNumSFcnParams(S) != ssGetSFcnParamsCount(S)) { - return; /* Parameter mismatch will be reported by Simulink */ - } - - if (!ssSetNumInputPorts(S, 1)) return; - - ssSetInputPortDirectFeedThrough(S, 0, 1); - ssSetInputPortRequiredContiguous(S, 0, 1); - ssSetInputPortDataType(S, 0, SS_UINT8); - ssSetInputPortVectorDimension(S, 0, MAVLINK_MAX_PACKET_LEN); - - if (!ssSetNumOutputPorts(S, 4)) return; - - #if defined(MATLAB_MEX_FILE) - if (ssGetSimMode(S) != SS_SIMMODE_SIZES_CALL_ONLY) - { - DTypeId dataTypeIdReg0; - ssRegisterTypeFromNamedObject(S, BUS_NAME_GA_PAYLOAD_FEEDBACK, &dataTypeIdReg0); - if (dataTypeIdReg0 == INVALID_DTYPE_ID) return; - ssSetOutputPortDataType(S, 0, dataTypeIdReg0); - - DTypeId dataTypeIdReg1; - ssRegisterTypeFromNamedObject(S, BUS_NAME_GA_PAYLOAD_COMMANDS, &dataTypeIdReg1); - if (dataTypeIdReg1 == INVALID_DTYPE_ID) return; - ssSetOutputPortDataType(S, 1, dataTypeIdReg1); - - DTypeId dataTypeIdReg2; - ssRegisterTypeFromNamedObject(S, BUS_NAME_DATA96, &dataTypeIdReg2); - if (dataTypeIdReg2 == INVALID_DTYPE_ID) return; - ssSetOutputPortDataType(S, 2, dataTypeIdReg2); - - DTypeId dataTypeIdReg3; - ssRegisterTypeFromNamedObject(S, BUS_NAME_HEARTBEAT, &dataTypeIdReg3); - if (dataTypeIdReg3 == INVALID_DTYPE_ID) return; - ssSetOutputPortDataType(S, 3, dataTypeIdReg3); - - } - #endif - - ssSetBusOutputObjectName(S, 0, (void *) BUS_NAME_GA_PAYLOAD_FEEDBACK); - ssSetBusOutputObjectName(S, 1, (void *) BUS_NAME_GA_PAYLOAD_COMMANDS); - ssSetBusOutputObjectName(S, 2, (void *) BUS_NAME_DATA96); - ssSetBusOutputObjectName(S, 3, (void *) BUS_NAME_HEARTBEAT); - - ssSetOutputPortWidth(S, 0, 1); - ssSetOutputPortWidth(S, 1, 1); - ssSetOutputPortWidth(S, 2, 1); - ssSetOutputPortWidth(S, 3, 1); - - ssSetBusOutputAsStruct(S, 0, 1); - ssSetBusOutputAsStruct(S, 1, 1); - ssSetBusOutputAsStruct(S, 2, 1); - ssSetBusOutputAsStruct(S, 3, 1); - - ssSetOutputPortBusMode(S, 0, SL_BUS_MODE); - ssSetOutputPortBusMode(S, 1, SL_BUS_MODE); - ssSetOutputPortBusMode(S, 2, SL_BUS_MODE); - ssSetOutputPortBusMode(S, 3, SL_BUS_MODE); - - ssSetNumSampleTimes(S, 1); - - /* specify the sim state compliance to be same as a built-in block */ - ssSetSimStateCompliance(S, USE_DEFAULT_SIM_STATE); - - ssSetOptions(S, 0); /* general options (SS_OPTION_xx) */ - -} /* end mdlInitializeSizes */ - - -/* Function: mdlInitializeSampleTimes ========================================== - * REQUIRED METHOD - * Abstract: - * This function is used to specify the sample time(s) for your - * S-function. You must register the same number of sample times as - * specified in ssSetNumSampleTimes. - */ -static void mdlInitializeSampleTimes(SimStruct *S) -{ - /* Register one pair for each sample time */ - ssSetSampleTime(S, 0, INHERITED_SAMPLE_TIME); - ssSetOffsetTime(S, 0, 0.0); - ssSetModelReferenceSampleTimeDefaultInheritance(S); - -} /* end mdlInitializeSampleTimes */ - -/* Function: mdlStart ========================================================== - * Abstract: - * This function is called once at start of model execution. If you - * have states that should be initialized once, this is the place - * to do it. - */ -#define MDL_START -static void mdlStart(SimStruct *S) -{ - int_T *busInfo = (int_T *) malloc(2*NFIELDS_OUTPUT_BUS*sizeof(int_T)); - if(busInfo == NULL) { - ssSetErrorStatus(S, "Memory allocation failure"); - return; - } - - encode_businfo_ga_payload_feedback(S, busInfo, OFFSET_GA_PAYLOAD_FEEDBACK); - encode_businfo_ga_payload_commands(S, busInfo, OFFSET_GA_PAYLOAD_COMMANDS); - encode_businfo_data96(S, busInfo, OFFSET_DATA96); - encode_businfo_heartbeat(S, busInfo, OFFSET_HEARTBEAT); - - ssSetUserData(S, busInfo); -} /* end mdlStart */ - - -/* Function: mdlOutputs ======================================================== - * REQUIRED METHOD - * Abstract: - * In this function, you compute the outputs of your S-function - * block. - */ -static void mdlOutputs(SimStruct *S, int_T tid) -{ - - int_T len_uvec = ssGetInputPortWidth(S, 0); - const uint8_T* uvec = (uint8_T*) ssGetInputPortSignal(S, 0); - - mavlink_message_t msg; - mavlink_status_t status; - - for (int uidx = 0; uidx < len_uvec; uidx++) { - if(mavlink_parse_char(MAVLINK_COMM_0, uvec[uidx], &msg, &status)) { - decode_mavlink_msg(S, &msg); - } - } - -} - -/* Function: mdlTerminate ====================================================== - * REQUIRED METHOD - * Abstract: - * In this function, you should perform any actions that are necessary - * at the termination of a simulation. For example, if memory was - * allocated in mdlStart, this is the place to free it. - */ - static void mdlTerminate(SimStruct *S) - { - /* Free stored bus information */ - int_T *busInfo = (int_T *) ssGetUserData(S); - if(busInfo != NULL) { - free(busInfo); - } - } - -/*=============================* - * Required S-function trailer * - *=============================*/ - -#ifdef MATLAB_MEX_FILE /* Is this file being compiled as a MEX-file? */ -#include "simulink.c" /* MEX-file interface mechanism */ -#else -#include "cg_sfun.h" /* Code generation registration function */ -#endif - diff --git a/sfunctions/sfun_decode_mavlink.mexw64 b/sfunctions/sfun_decode_mavlink.mexw64 deleted file mode 100644 index 9f79601..0000000 Binary files a/sfunctions/sfun_decode_mavlink.mexw64 and /dev/null differ diff --git a/sfunctions/sfun_encode_msg_attitude.cpp b/sfunctions/sfun_encode_msg_attitude.cpp deleted file mode 100644 index 7ca0bf1..0000000 --- a/sfunctions/sfun_encode_msg_attitude.cpp +++ /dev/null @@ -1,137 +0,0 @@ -/* -DO NOT EDIT. -This file was automatically created by the Matlab function 'create_sfun_encode' on 05-Dec-2017 13:24:40 -as part of Simulink MAVLink library. -*/ -#define S_FUNCTION_NAME sfun_encode_msg_attitude -#define S_FUNCTION_LEVEL 2 - -#include "simstruc.h" - -// System and Component IDs for MAVLink communication -#define SYS_ID 100 -#define COMP_ID 200 - -#include "include/mavlink/v1.0/common/mavlink.h" -#include "include/sfun_mavlink_msg_attitude.h" - -/* Function: mdlInitializeSizes ================================================ - * REQUIRED METHOD - * Abstract: - * The sizes information is used by Simulink to determine the S-function - * block's characteristics (number of inputs, outputs, states, etc.). - */ -static void mdlInitializeSizes(SimStruct *S) -{ - - DECL_AND_INIT_DIMSINFO(inputDimsInfo); - DECL_AND_INIT_DIMSINFO(outputDimsInfo); - - ssSetNumSFcnParams(S, 0); - if (ssGetNumSFcnParams(S) != ssGetSFcnParamsCount(S)) { - return; /* Parameter mismatch will be reported by Simulink */ - } - - if (!ssSetNumInputPorts(S, 1)) return; - - ssSetInputPortWidth(S, 0, 1); - ssSetInputPortDirectFeedThrough(S, 0, 1); - ssSetInputPortRequiredContiguous(S, 0, 1); - - DTypeId BusType; - ssRegisterTypeFromNamedObject(S, BUS_NAME_ATTITUDE, &BusType); - if(BusType == INVALID_DTYPE_ID) return; - ssSetInputPortDataType(S, 0, BusType); - ssSetBusInputAsStruct(S, 0, 1); - ssSetInputPortBusMode(S, 0, SL_BUS_MODE); - - if (!ssSetNumOutputPorts(S, 1)) return; - - ssSetOutputPortWidth(S, 0, ENCODED_LEN_ATTITUDE); - ssSetOutputPortDataType(S, 0, SS_UINT8); - - ssSetNumSampleTimes(S, 1); - - /* specify the sim state compliance to be same as a built-in block */ - ssSetSimStateCompliance(S, USE_DEFAULT_SIM_STATE); - - ssSetOptions(S, 0); /* general options (SS_OPTION_xx) */ - -} /* end mdlInitializeSizes */ - - -/* Function: mdlInitializeSampleTimes ========================================== - * REQUIRED METHOD - * Abstract: - * This function is used to specify the sample time(s) for your - * S-function. You must register the same number of sample times as - * specified in ssSetNumSampleTimes. - */ -static void mdlInitializeSampleTimes(SimStruct *S) -{ - /* Register one pair for each sample time */ - ssSetSampleTime(S, 0, INHERITED_SAMPLE_TIME); - ssSetOffsetTime(S, 0, 0.0); - ssSetModelReferenceSampleTimeDefaultInheritance(S); - -} /* end mdlInitializeSampleTimes */ - -/* Function: mdlStart ========================================================== - * Abstract: - * This function is called once at start of model execution. If you - * have states that should be initialized once, this is the place - * to do it. - */ -#define MDL_START -static void mdlStart(SimStruct *S) -{ - int_T *busInfo = (int_T *) malloc(2*NFIELDS_BUS_ATTITUDE*sizeof(int_T)); - if(busInfo == NULL) { - ssSetErrorStatus(S, "Memory allocation failure"); - return; - } - encode_businfo_attitude(S, busInfo, 0); - -} /* end mdlStart */ - - -/* Function: mdlOutputs ======================================================== - * REQUIRED METHOD - * Abstract: - * In this function, you compute the outputs of your S-function - * block. - */ -static void mdlOutputs(SimStruct *S, int_T tid) -{ - const char *uvec = (const char *) ssGetInputPortSignal(S, 0); - uint8_T *yvec = (uint8_T *) ssGetOutputPortSignal(S, 0); - int_T* busInfo = (int_T *) ssGetUserData(S); - encode_vector_attitude(uvec, busInfo, yvec, 0); -} - -/* Function: mdlTerminate ====================================================== - * REQUIRED METHOD - * Abstract: - * In this function, you should perform any actions that are necessary - * at the termination of a simulation. For example, if memory was - * allocated in mdlStart, this is the place to free it. - */ - static void mdlTerminate(SimStruct *S) - { - /* Free stored bus information */ - int_T *busInfo = (int_T *) ssGetUserData(S); - if(busInfo != NULL) { - free(busInfo); - } - } - -/*=============================* - * Required S-function trailer * - *=============================*/ - -#ifdef MATLAB_MEX_FILE /* Is this file being compiled as a MEX-file? */ -#include "simulink.c" /* MEX-file interface mechanism */ -#else -#include "cg_sfun.h" /* Code generation registration function */ -#endif - diff --git a/sfunctions/sfun_encode_msg_attitude.mexw64 b/sfunctions/sfun_encode_msg_attitude.mexw64 deleted file mode 100644 index f32501c..0000000 Binary files a/sfunctions/sfun_encode_msg_attitude.mexw64 and /dev/null differ diff --git a/sfunctions/sfun_encode_msg_heartbeat.cpp b/sfunctions/sfun_encode_msg_heartbeat.cpp deleted file mode 100644 index 66d2d41..0000000 --- a/sfunctions/sfun_encode_msg_heartbeat.cpp +++ /dev/null @@ -1,137 +0,0 @@ -/* -DO NOT EDIT. -This file was automatically created by the Matlab function 'create_sfun_encode' on 03-Feb-2018 14:21:37 -as part of Simulink MAVLink library. -*/ -#define S_FUNCTION_NAME sfun_encode_msg_heartbeat -#define S_FUNCTION_LEVEL 2 - -#include "simstruc.h" - -// System and Component IDs for MAVLink communication -#define SYS_ID 100 -#define COMP_ID 200 - -#include "D:\simulink_mavlink\include\mavlink\v2.0\common\mavlink.h" -#include "D:\simulink_mavlink\include\sfun_mavlink_msg_heartbeat.h" - -/* Function: mdlInitializeSizes ================================================ - * REQUIRED METHOD - * Abstract: - * The sizes information is used by Simulink to determine the S-function - * block's characteristics (number of inputs, outputs, states, etc.). - */ -static void mdlInitializeSizes(SimStruct *S) -{ - - DECL_AND_INIT_DIMSINFO(inputDimsInfo); - DECL_AND_INIT_DIMSINFO(outputDimsInfo); - - ssSetNumSFcnParams(S, 0); - if (ssGetNumSFcnParams(S) != ssGetSFcnParamsCount(S)) { - return; /* Parameter mismatch will be reported by Simulink */ - } - - if (!ssSetNumInputPorts(S, 1)) return; - - ssSetInputPortWidth(S, 0, 1); - ssSetInputPortDirectFeedThrough(S, 0, 1); - ssSetInputPortRequiredContiguous(S, 0, 1); - - DTypeId BusType; - ssRegisterTypeFromNamedObject(S, BUS_NAME_HEARTBEAT, &BusType); - if(BusType == INVALID_DTYPE_ID) return; - ssSetInputPortDataType(S, 0, BusType); - ssSetBusInputAsStruct(S, 0, 1); - ssSetInputPortBusMode(S, 0, SL_BUS_MODE); - - if (!ssSetNumOutputPorts(S, 1)) return; - - ssSetOutputPortWidth(S, 0, ENCODED_LEN_HEARTBEAT); - ssSetOutputPortDataType(S, 0, SS_UINT8); - - ssSetNumSampleTimes(S, 1); - - /* specify the sim state compliance to be same as a built-in block */ - ssSetSimStateCompliance(S, USE_DEFAULT_SIM_STATE); - - ssSetOptions(S, 0); /* general options (SS_OPTION_xx) */ - -} /* end mdlInitializeSizes */ - - -/* Function: mdlInitializeSampleTimes ========================================== - * REQUIRED METHOD - * Abstract: - * This function is used to specify the sample time(s) for your - * S-function. You must register the same number of sample times as - * specified in ssSetNumSampleTimes. - */ -static void mdlInitializeSampleTimes(SimStruct *S) -{ - /* Register one pair for each sample time */ - ssSetSampleTime(S, 0, INHERITED_SAMPLE_TIME); - ssSetOffsetTime(S, 0, 0.0); - ssSetModelReferenceSampleTimeDefaultInheritance(S); - -} /* end mdlInitializeSampleTimes */ - -/* Function: mdlStart ========================================================== - * Abstract: - * This function is called once at start of model execution. If you - * have states that should be initialized once, this is the place - * to do it. - */ -#define MDL_START -static void mdlStart(SimStruct *S) -{ - int_T *busInfo = (int_T *) malloc(2*NFIELDS_BUS_HEARTBEAT*sizeof(int_T)); - if(busInfo == NULL) { - ssSetErrorStatus(S, "Memory allocation failure"); - return; - } - encode_businfo_heartbeat(S, busInfo, 0); - -} /* end mdlStart */ - - -/* Function: mdlOutputs ======================================================== - * REQUIRED METHOD - * Abstract: - * In this function, you compute the outputs of your S-function - * block. - */ -static void mdlOutputs(SimStruct *S, int_T tid) -{ - const char *uvec = (const char *) ssGetInputPortSignal(S, 0); - uint8_T *yvec = (uint8_T *) ssGetOutputPortSignal(S, 0); - int_T* busInfo = (int_T *) ssGetUserData(S); - encode_vector_heartbeat(uvec, busInfo, yvec, 0); -} - -/* Function: mdlTerminate ====================================================== - * REQUIRED METHOD - * Abstract: - * In this function, you should perform any actions that are necessary - * at the termination of a simulation. For example, if memory was - * allocated in mdlStart, this is the place to free it. - */ - static void mdlTerminate(SimStruct *S) - { - /* Free stored bus information */ - int_T *busInfo = (int_T *) ssGetUserData(S); - if(busInfo != NULL) { - free(busInfo); - } - } - -/*=============================* - * Required S-function trailer * - *=============================*/ - -#ifdef MATLAB_MEX_FILE /* Is this file being compiled as a MEX-file? */ -#include "simulink.c" /* MEX-file interface mechanism */ -#else -#include "cg_sfun.h" /* Code generation registration function */ -#endif - diff --git a/sfunctions/sfun_encode_msg_heartbeat.mexw64 b/sfunctions/sfun_encode_msg_heartbeat.mexw64 deleted file mode 100644 index cb82fae..0000000 Binary files a/sfunctions/sfun_encode_msg_heartbeat.mexw64 and /dev/null differ diff --git a/sfunctions/sfun_encode_msg_raw_imu.cpp b/sfunctions/sfun_encode_msg_raw_imu.cpp deleted file mode 100644 index 1c26fef..0000000 --- a/sfunctions/sfun_encode_msg_raw_imu.cpp +++ /dev/null @@ -1,137 +0,0 @@ -/* -DO NOT EDIT. -This file was automatically created by the Matlab function 'create_sfun_encode' on 05-Dec-2017 13:24:41 -as part of Simulink MAVLink library. -*/ -#define S_FUNCTION_NAME sfun_encode_msg_raw_imu -#define S_FUNCTION_LEVEL 2 - -#include "simstruc.h" - -// System and Component IDs for MAVLink communication -#define SYS_ID 100 -#define COMP_ID 200 - -#include "include/mavlink/v1.0/common/mavlink.h" -#include "include/sfun_mavlink_msg_raw_imu.h" - -/* Function: mdlInitializeSizes ================================================ - * REQUIRED METHOD - * Abstract: - * The sizes information is used by Simulink to determine the S-function - * block's characteristics (number of inputs, outputs, states, etc.). - */ -static void mdlInitializeSizes(SimStruct *S) -{ - - DECL_AND_INIT_DIMSINFO(inputDimsInfo); - DECL_AND_INIT_DIMSINFO(outputDimsInfo); - - ssSetNumSFcnParams(S, 0); - if (ssGetNumSFcnParams(S) != ssGetSFcnParamsCount(S)) { - return; /* Parameter mismatch will be reported by Simulink */ - } - - if (!ssSetNumInputPorts(S, 1)) return; - - ssSetInputPortWidth(S, 0, 1); - ssSetInputPortDirectFeedThrough(S, 0, 1); - ssSetInputPortRequiredContiguous(S, 0, 1); - - DTypeId BusType; - ssRegisterTypeFromNamedObject(S, BUS_NAME_RAW_IMU, &BusType); - if(BusType == INVALID_DTYPE_ID) return; - ssSetInputPortDataType(S, 0, BusType); - ssSetBusInputAsStruct(S, 0, 1); - ssSetInputPortBusMode(S, 0, SL_BUS_MODE); - - if (!ssSetNumOutputPorts(S, 1)) return; - - ssSetOutputPortWidth(S, 0, ENCODED_LEN_RAW_IMU); - ssSetOutputPortDataType(S, 0, SS_UINT8); - - ssSetNumSampleTimes(S, 1); - - /* specify the sim state compliance to be same as a built-in block */ - ssSetSimStateCompliance(S, USE_DEFAULT_SIM_STATE); - - ssSetOptions(S, 0); /* general options (SS_OPTION_xx) */ - -} /* end mdlInitializeSizes */ - - -/* Function: mdlInitializeSampleTimes ========================================== - * REQUIRED METHOD - * Abstract: - * This function is used to specify the sample time(s) for your - * S-function. You must register the same number of sample times as - * specified in ssSetNumSampleTimes. - */ -static void mdlInitializeSampleTimes(SimStruct *S) -{ - /* Register one pair for each sample time */ - ssSetSampleTime(S, 0, INHERITED_SAMPLE_TIME); - ssSetOffsetTime(S, 0, 0.0); - ssSetModelReferenceSampleTimeDefaultInheritance(S); - -} /* end mdlInitializeSampleTimes */ - -/* Function: mdlStart ========================================================== - * Abstract: - * This function is called once at start of model execution. If you - * have states that should be initialized once, this is the place - * to do it. - */ -#define MDL_START -static void mdlStart(SimStruct *S) -{ - int_T *busInfo = (int_T *) malloc(2*NFIELDS_BUS_RAW_IMU*sizeof(int_T)); - if(busInfo == NULL) { - ssSetErrorStatus(S, "Memory allocation failure"); - return; - } - encode_businfo_raw_imu(S, busInfo, 0); - -} /* end mdlStart */ - - -/* Function: mdlOutputs ======================================================== - * REQUIRED METHOD - * Abstract: - * In this function, you compute the outputs of your S-function - * block. - */ -static void mdlOutputs(SimStruct *S, int_T tid) -{ - const char *uvec = (const char *) ssGetInputPortSignal(S, 0); - uint8_T *yvec = (uint8_T *) ssGetOutputPortSignal(S, 0); - int_T* busInfo = (int_T *) ssGetUserData(S); - encode_vector_raw_imu(uvec, busInfo, yvec, 0); -} - -/* Function: mdlTerminate ====================================================== - * REQUIRED METHOD - * Abstract: - * In this function, you should perform any actions that are necessary - * at the termination of a simulation. For example, if memory was - * allocated in mdlStart, this is the place to free it. - */ - static void mdlTerminate(SimStruct *S) - { - /* Free stored bus information */ - int_T *busInfo = (int_T *) ssGetUserData(S); - if(busInfo != NULL) { - free(busInfo); - } - } - -/*=============================* - * Required S-function trailer * - *=============================*/ - -#ifdef MATLAB_MEX_FILE /* Is this file being compiled as a MEX-file? */ -#include "simulink.c" /* MEX-file interface mechanism */ -#else -#include "cg_sfun.h" /* Code generation registration function */ -#endif - diff --git a/sfunctions/sfun_encode_msg_raw_imu.mexw64 b/sfunctions/sfun_encode_msg_raw_imu.mexw64 deleted file mode 100644 index 9fc6620..0000000 Binary files a/sfunctions/sfun_encode_msg_raw_imu.mexw64 and /dev/null differ