mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-10 06:59:54 +08:00
Merge pull request #1028 from paparazzi/mavlink_module
Very simple mavlink module that sends some basic messages. A lot of things (like mav type, sensors, status, etc...) are still fixed and hardcoded, but good enough for first tests I guess...
This commit is contained in:
@@ -0,0 +1,226 @@
|
||||
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
|
||||
|
||||
<!-- this is a quadrotor frame in X-configuration equiped with
|
||||
* Autopilot: Lisa/MX 2.1 with STM32F4 http://wiki.paparazziuav.org/wiki/Lisa/M_v21
|
||||
* IMU: Integrated Aspirin 2.2 http://wiki.paparazziuav.org/wiki/AspirinIMU
|
||||
* Actuators: PWM motor controllers http://wiki.paparazziuav.org/wiki/Subsystem/actuators#PWM
|
||||
* GPS: Ublox http://wiki.paparazziuav.org/wiki/Subsystem/gps
|
||||
* RC: two Spektrum sats http://wiki.paparazziuav.org/wiki/Subsystem/radio_control#Spektrum
|
||||
|
||||
This airframe is meant for testing the mavlink module and will:
|
||||
- send normal Paparazzi telemetry on the modem uart
|
||||
- send mavlink messages on usb serial or via UDP in nps simulation
|
||||
-->
|
||||
|
||||
<airframe name="Quadrotor LisaMX_2.1 pwm">
|
||||
|
||||
<firmware name="rotorcraft">
|
||||
<target name="ap" board="lisa_mx_2.1">
|
||||
<!-- MPU6000 is configured to output data at 2kHz, but polled at 512Hz PERIODIC_FREQUENCY -->
|
||||
<configure name="MAVLINK_PORT" value="UsbS"/>
|
||||
</target>
|
||||
|
||||
<target name="nps" board="pc">
|
||||
<subsystem name="fdm" type="jsbsim"/>
|
||||
<configure name="MAVLINK_PORT" value="UDP0"/>
|
||||
</target>
|
||||
|
||||
<subsystem name="radio_control" type="spektrum">
|
||||
<define name="RADIO_MODE" value="RADIO_AUX1"/>
|
||||
<configure name="USE_SECONDARY_SPEKTRUM_RECEIVER" value="1"/>
|
||||
</subsystem>
|
||||
|
||||
<subsystem name="motor_mixing"/>
|
||||
<subsystem name="actuators" type="pwm">
|
||||
<define name="SERVO_HZ" value="400"/>
|
||||
</subsystem>
|
||||
|
||||
<subsystem name="telemetry" type="transparent"/>
|
||||
<subsystem name="imu" type="lisa_mx_v2.1"/>
|
||||
<subsystem name="gps" type="ublox"/>
|
||||
<subsystem name="stabilization" type="int_quat"/>
|
||||
<subsystem name="ahrs" type="float_mlkf"/>
|
||||
<subsystem name="ins" type="hff"/>
|
||||
|
||||
<!--define name="KILL_ON_GROUND_DETECT" value="TRUE"/-->
|
||||
</firmware>
|
||||
|
||||
<modules>
|
||||
<load name="gps_ubx_ucenter.xml"/>
|
||||
<load name="geo_mag.xml"/>
|
||||
<load name="air_data.xml"/>
|
||||
<load name="mavlink.xml">
|
||||
<!--configure name="MAVLINK_PORT" value="UsbS"/-->
|
||||
</load>
|
||||
</modules>
|
||||
|
||||
<servos driver="Pwm">
|
||||
<servo name="FRONT" no="0" min="1000" neutral="1100" max="1900"/>
|
||||
<servo name="BACK" no="1" min="1000" neutral="1100" max="1900"/>
|
||||
<servo name="RIGHT" no="2" min="1000" neutral="1100" max="1900"/>
|
||||
<servo name="LEFT" no="3" min="1000" neutral="1100" max="1900"/>
|
||||
</servos>
|
||||
|
||||
<commands>
|
||||
<axis name="ROLL" failsafe_value="0"/>
|
||||
<axis name="PITCH" failsafe_value="0"/>
|
||||
<axis name="YAW" failsafe_value="0"/>
|
||||
<axis name="THRUST" failsafe_value="0"/>
|
||||
</commands>
|
||||
|
||||
<section name="MIXING" prefix="MOTOR_MIXING_">
|
||||
<define name="TRIM_ROLL" value="0"/>
|
||||
<define name="TRIM_PITCH" value="0"/>
|
||||
<define name="TRIM_YAW" value="0"/>
|
||||
<define name="NB_MOTOR" value="4"/>
|
||||
<define name="SCALE" value="256"/>
|
||||
<!-- order (and rotation direction) : NE (CW), SE (CCW), SW (CW), NW (CCW) -->
|
||||
<define name="ROLL_COEF" value="{ -256, -256, 256, 256 }"/>
|
||||
<define name="PITCH_COEF" value="{ 256, -256, -256, 256 }"/>
|
||||
<define name="YAW_COEF" value="{ -256, 256, -256, 256 }"/>
|
||||
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
|
||||
</section>
|
||||
|
||||
<command_laws>
|
||||
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
|
||||
<set servo="FRONT" value="motor_mixing.commands[0]"/>
|
||||
<set servo="BACK" value="motor_mixing.commands[1]"/>
|
||||
<set servo="RIGHT" value="motor_mixing.commands[2]"/>
|
||||
<set servo="LEFT" value="motor_mixing.commands[3]"/>
|
||||
</command_laws>
|
||||
|
||||
<section name="IMU" prefix="IMU_">
|
||||
<define name="ACCEL_X_NEUTRAL" value="11"/>
|
||||
<define name="ACCEL_Y_NEUTRAL" value="11"/>
|
||||
<define name="ACCEL_Z_NEUTRAL" value="-25"/>
|
||||
|
||||
<!-- replace this with your own calibration -->
|
||||
<define name="MAG_X_NEUTRAL" value="-179"/>
|
||||
<define name="MAG_Y_NEUTRAL" value="-21"/>
|
||||
<define name="MAG_Z_NEUTRAL" value="79"/>
|
||||
<define name="MAG_X_SENS" value="4.17334785618" integer="16"/>
|
||||
<define name="MAG_Y_SENS" value="3.98885954135" integer="16"/>
|
||||
<define name="MAG_Z_SENS" value="4.40442339014" integer="16"/>
|
||||
|
||||
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
|
||||
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
|
||||
</section>
|
||||
|
||||
<section name="AHRS" prefix="AHRS_">
|
||||
<!-- values used if no GPS fix, on 3D fix is update by geo_mag module -->
|
||||
<define name="H_X" value="0.3770441"/>
|
||||
<define name="H_Y" value="0.0193986"/>
|
||||
<define name="H_Z" value="0.9259921"/>
|
||||
</section>
|
||||
|
||||
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_P" value="10000"/>
|
||||
<define name="SP_MAX_Q" value="10000"/>
|
||||
<define name="SP_MAX_R" value="10000"/>
|
||||
<define name="DEADBAND_P" value="20"/>
|
||||
<define name="DEADBAND_Q" value="20"/>
|
||||
<define name="DEADBAND_R" value="200"/>
|
||||
<define name="REF_TAU" value="4"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="GAIN_P" value="400"/>
|
||||
<define name="GAIN_Q" value="400"/>
|
||||
<define name="GAIN_R" value="350"/>
|
||||
|
||||
<define name="IGAIN_P" value="75"/>
|
||||
<define name="IGAIN_Q" value="75"/>
|
||||
<define name="IGAIN_R" value="50"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="DDGAIN_P" value="300"/>
|
||||
<define name="DDGAIN_Q" value="300"/>
|
||||
<define name="DDGAIN_R" value="300"/>
|
||||
</section>
|
||||
|
||||
|
||||
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
|
||||
<!-- setpoints -->
|
||||
<define name="SP_MAX_PHI" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_THETA" value="45." unit="deg"/>
|
||||
<define name="SP_MAX_R" value="90." unit="deg/s"/>
|
||||
<define name="DEADBAND_A" value="0"/>
|
||||
<define name="DEADBAND_E" value="0"/>
|
||||
<define name="DEADBAND_R" value="250"/>
|
||||
|
||||
<!-- reference -->
|
||||
<define name="REF_OMEGA_P" value="400" unit="deg/s"/>
|
||||
<define name="REF_ZETA_P" value="0.85"/>
|
||||
<define name="REF_MAX_P" value="400." unit="deg/s"/>
|
||||
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_Q" value="400" unit="deg/s"/>
|
||||
<define name="REF_ZETA_Q" value="0.85"/>
|
||||
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
|
||||
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
|
||||
|
||||
<define name="REF_OMEGA_R" value="250" unit="deg/s"/>
|
||||
<define name="REF_ZETA_R" value="0.85"/>
|
||||
<define name="REF_MAX_R" value="180." unit="deg/s"/>
|
||||
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
|
||||
|
||||
<!-- feedback -->
|
||||
<define name="PHI_PGAIN" value="1000"/>
|
||||
<define name="PHI_DGAIN" value="400"/>
|
||||
<define name="PHI_IGAIN" value="200"/>
|
||||
|
||||
<define name="THETA_PGAIN" value="1000"/>
|
||||
<define name="THETA_DGAIN" value="400"/>
|
||||
<define name="THETA_IGAIN" value="200"/>
|
||||
|
||||
<define name="PSI_PGAIN" value="500"/>
|
||||
<define name="PSI_DGAIN" value="300"/>
|
||||
<define name="PSI_IGAIN" value="10"/>
|
||||
|
||||
<!-- feedforward -->
|
||||
<define name="PHI_DDGAIN" value="300"/>
|
||||
<define name="THETA_DDGAIN" value="300"/>
|
||||
<define name="PSI_DDGAIN" value="300"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
|
||||
<define name="HOVER_KP" value="150"/>
|
||||
<define name="HOVER_KD" value="80"/>
|
||||
<define name="HOVER_KI" value="20"/>
|
||||
<define name="NOMINAL_HOVER_THROTTLE" value="0.5"/>
|
||||
<define name="ADAPT_THROTTLE_ENABLED" value="TRUE"/>
|
||||
</section>
|
||||
|
||||
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
|
||||
<define name="MAX_BANK" value="20" unit="deg"/>
|
||||
<define name="USE_SPEED_REF" value="TRUE"/>
|
||||
<define name="PGAIN" value="50"/>
|
||||
<define name="DGAIN" value="100"/>
|
||||
<define name="AGAIN" value="70"/>
|
||||
<define name="IGAIN" value="20"/>
|
||||
</section>
|
||||
|
||||
<section name="SIMULATOR" prefix="NPS_">
|
||||
<define name="ACTUATOR_NAMES" value="{"ne_motor", "se_motor", "sw_motor", "nw_motor"}"/>
|
||||
<define name="JSBSIM_INIT" value=""reset00""/>
|
||||
<define name="JSBSIM_MODEL" value=""simple_x_quad""/>
|
||||
<define name="SENSORS_PARAMS" value=""nps_sensors_params_default.h""/>
|
||||
<!-- mode switch on joystick channel 5 (axis numbering starting at zero) -->
|
||||
<define name="JS_AXIS_MODE" value="4"/>
|
||||
</section>
|
||||
|
||||
<section name="AUTOPILOT">
|
||||
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
|
||||
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD"/>
|
||||
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
|
||||
</section>
|
||||
|
||||
<section name="BAT">
|
||||
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
|
||||
<define name="CRITIC_BAT_LEVEL" value="9.6" unit="V"/>
|
||||
<define name="LOW_BAT_LEVEL" value="10.1" unit="V"/>
|
||||
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
|
||||
</section>
|
||||
|
||||
</airframe>
|
||||
@@ -351,6 +351,17 @@
|
||||
settings_modules=""
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
name="quad_mavlink"
|
||||
ac_id="1"
|
||||
airframe="airframes/examples/quadrotor_lisa_mx_mavlink.xml"
|
||||
radio="radios/spektrum.xml"
|
||||
telemetry="telemetry/default_rotorcraft.xml"
|
||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_float_mlkf.xml settings/control/rotorcraft_guidance.xml settings/control/stabilization_att_int_quat.xml"
|
||||
settings_modules="modules/gps_ubx_ucenter.xml modules/air_data.xml"
|
||||
gui_color="blue"
|
||||
/>
|
||||
<aircraft
|
||||
name="quadshot"
|
||||
ac_id="19"
|
||||
|
||||
@@ -0,0 +1,40 @@
|
||||
<!DOCTYPE module SYSTEM "module.dtd">
|
||||
|
||||
<module name="datalink">
|
||||
<doc>
|
||||
<description>Basic MAVLink implementation</description>
|
||||
<configure name="MAVLINK_PORT" value="UARTx|UDPx|UsbS" description="The port device to use for mavlink (default: UART1)"/>
|
||||
<configure name="MAVLINK_BAUD" value="B57600" description="Baud rate if MAVLINK_PORT is a UART"/>
|
||||
</doc>
|
||||
<header>
|
||||
<file name="mavlink.h"/>
|
||||
</header>
|
||||
|
||||
<init fun="mavlink_init()"/>
|
||||
<periodic fun="mavlink_periodic()" freq="10" autorun="TRUE"/>
|
||||
<event fun="mavlink_event()"/>
|
||||
|
||||
<makefile>
|
||||
<file name="mavlink.c"/>
|
||||
<raw>
|
||||
MAVLINK_PORT ?= UART1
|
||||
MAVLINK_PORT_UPPER=$(shell echo $(MAVLINK_PORT) | tr a-z A-Z)
|
||||
ifeq ($(MAVLINK_PORT), UsbS)
|
||||
ap.CFLAGS += -DUSE_USB_SERIAL
|
||||
ap.srcs += $(SRC_ARCH)/usb_ser_hw.c
|
||||
ap.CFLAGS += -DMAVLINK_DEV=UsbS
|
||||
else
|
||||
ifeq ($(findstring UDP,$(MAVLINK_PORT)), UDP)
|
||||
include $(CFG_SHARED)/udp.makefile
|
||||
$(TARGET).CFLAGS += -DMAVLINK_DEV=$(MAVLINK_PORT_UPPER)
|
||||
$(TARGET).CFLAGS += -DUSE_$(MAVLINK_PORT_UPPER)
|
||||
else
|
||||
MAVLINK_BAUD ?= B57600
|
||||
ap.CFLAGS += -DMAVLINK_DEV=$(MAVLINK_PORT_UPPER)
|
||||
ap.CFLAGS += -DUSE_$(MAVLINK_PORT_UPPER)
|
||||
ap.CFLAGS += -D$(MAVLINK_PORT_UPPER)_BAUD=$(MAVLINK_BAUD)
|
||||
endif
|
||||
endif
|
||||
</raw>
|
||||
</makefile>
|
||||
</module>
|
||||
@@ -0,0 +1,404 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freek van Tienen <freek.v.tienen@gmail.com>
|
||||
*
|
||||
* This file is part of paparazzi.
|
||||
*
|
||||
* paparazzi is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 2, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* paparazzi is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with paparazzi; see the file COPYING. If not, write to
|
||||
* the Free Software Foundation, 59 Temple Place - Suite 330,
|
||||
* Boston, MA 02111-1307, USA.
|
||||
*
|
||||
*/
|
||||
|
||||
/** @file modules/datalink/mavlink.c
|
||||
* @brief Basic MAVLink datalink implementation
|
||||
*/
|
||||
|
||||
#include "modules/datalink/mavlink.h"
|
||||
|
||||
// include mavlink headers, but ignore some warnings
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wswitch-default"
|
||||
#include "mavlink/paparazzi/mavlink.h"
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
#include "generated/airframe.h"
|
||||
#include "generated/modules.h"
|
||||
#include "generated/settings.h"
|
||||
|
||||
#include "mcu_periph/sys_time.h"
|
||||
#include "subsystems/electrical.h"
|
||||
#include "state.h"
|
||||
|
||||
mavlink_system_t mavlink_system;
|
||||
|
||||
static uint8_t mavlink_params_idx = NB_SETTING; /**< Transmitting parameters index */
|
||||
static char mavlink_params[NB_SETTING][16] = SETTINGS; /**< Transmitting parameter names */
|
||||
|
||||
static inline void mavlink_send_heartbeat(void);
|
||||
static inline void mavlink_send_sys_status(void);
|
||||
static inline void mavlink_send_attitude(void);
|
||||
static inline void mavlink_send_local_position_ned(void);
|
||||
static inline void mavlink_send_global_position_int(void);
|
||||
static inline void mavlink_send_params(void);
|
||||
static inline void mavlink_send_autopilot_version(void);
|
||||
static inline void mavlink_send_attitude_quaternion(void);
|
||||
static inline void mavlink_send_gps_raw_int(void);
|
||||
static inline void mavlink_send_rc_channels(void);
|
||||
static inline void mavlink_send_battery_status(void);
|
||||
|
||||
|
||||
/// TODO: FIXME
|
||||
#define UAV_SENSORS (MAV_SYS_STATUS_SENSOR_3D_GYRO|MAV_SYS_STATUS_SENSOR_3D_ACCEL|MAV_SYS_STATUS_SENSOR_3D_MAG|MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE)
|
||||
|
||||
/**
|
||||
* MAVLink initialization
|
||||
*/
|
||||
void mavlink_init(void)
|
||||
{
|
||||
mavlink_system.sysid = AC_ID; // System ID, 1-255
|
||||
mavlink_system.compid = MAV_COMP_ID_MISSIONPLANNER; // Component/Subsystem ID, 1-255
|
||||
}
|
||||
|
||||
/**
|
||||
* Periodic MAVLink calls.
|
||||
* Called at MAVLINK_PERIODIC_FREQUENCY (set in module xml to 10Hz)
|
||||
*/
|
||||
void mavlink_periodic(void)
|
||||
{
|
||||
RunOnceEvery(2, mavlink_send_heartbeat());
|
||||
RunOnceEvery(5, mavlink_send_sys_status());
|
||||
RunOnceEvery(5, mavlink_send_attitude());
|
||||
RunOnceEvery(5, mavlink_send_params());
|
||||
RunOnceEvery(4, mavlink_send_local_position_ned());
|
||||
RunOnceEvery(5, mavlink_send_global_position_int());
|
||||
RunOnceEvery(6, mavlink_send_gps_raw_int());
|
||||
RunOnceEvery(5, mavlink_send_attitude_quaternion());
|
||||
RunOnceEvery(5, mavlink_send_rc_channels());
|
||||
RunOnceEvery(21, mavlink_send_battery_status());
|
||||
RunOnceEvery(32, mavlink_send_autopilot_version());
|
||||
}
|
||||
|
||||
/**
|
||||
* Event MAVLink calls
|
||||
*/
|
||||
void mavlink_event(void)
|
||||
{
|
||||
int i, j;
|
||||
mavlink_message_t msg;
|
||||
mavlink_status_t status;
|
||||
|
||||
// Check uplink
|
||||
while (MAVLink(ChAvailable())) {
|
||||
char test = MAVLink(Getch());
|
||||
|
||||
// When we receive a message
|
||||
if (mavlink_parse_char(MAVLINK_COMM_0, test, &msg, &status)) {
|
||||
switch (msg.msgid) {
|
||||
case MAVLINK_MSG_ID_HEARTBEAT:
|
||||
break;
|
||||
|
||||
/* When requesting data streams say we can't send them */
|
||||
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: {
|
||||
mavlink_request_data_stream_t cmd;
|
||||
mavlink_msg_request_data_stream_decode(&msg, &cmd);
|
||||
|
||||
mavlink_msg_data_stream_send(MAVLINK_COMM_0, cmd.req_stream_id, 0, 0);
|
||||
MAVLink(SendMessage());
|
||||
break;
|
||||
}
|
||||
|
||||
/* Override channels with RC */
|
||||
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: {
|
||||
mavlink_rc_channels_override_t cmd;
|
||||
mavlink_msg_rc_channels_override_decode(&msg, &cmd);
|
||||
#if defined RADIO_CONTROL && defined RADIO_CONTROL_TYPE_DATALINK
|
||||
uint8_t thrust = (cmd.chan3_raw - 950) * 127 / 1100;
|
||||
int8_t roll = -(cmd.chan1_raw - 1500) * 255 / 1100 / 2;
|
||||
int8_t pitch = -(cmd.chan2_raw - 1500) * 255 / 1100 / 2;
|
||||
int8_t yaw = -(cmd.chan4_raw - 1500) * 255 / 1100;
|
||||
parse_rc_4ch_datalink(0, thrust, roll, pitch, yaw);
|
||||
//printf("RECEIVED: RC Channel Override for: %d/%d: throttle: %d; roll: %d; pitch: %d; yaw: %d;\r\n",
|
||||
// cmd.target_system, cmd.target_component, thrust, roll, pitch, yaw);
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
||||
/* When a request is made of the parameters list */
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
|
||||
mavlink_params_idx = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
/* When a request os made for a specific parameter */
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
|
||||
mavlink_param_request_read_t cmd;
|
||||
mavlink_msg_param_request_read_decode(&msg, &cmd);
|
||||
|
||||
// First check param_index and search for the ID if needed
|
||||
if (cmd.param_index == -1) {
|
||||
|
||||
// Go trough all the settings to search the ID
|
||||
for (i = 0; i < NB_SETTING; i++) {
|
||||
for (j = 0; j < 16; j++) {
|
||||
if (mavlink_params[i][j] != cmd.param_id[j]) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (mavlink_params[i][j] == '\0') {
|
||||
cmd.param_index = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (mavlink_params[i][j] == '\0') {
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
mavlink_msg_param_value_send(MAVLINK_COMM_0,
|
||||
mavlink_params[cmd.param_index],
|
||||
settings_get_value(cmd.param_index),
|
||||
MAV_PARAM_TYPE_REAL32,
|
||||
NB_SETTING,
|
||||
cmd.param_index);
|
||||
MAVLink(SendMessage());
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
default:
|
||||
//Do nothing
|
||||
//printf("Received message with id: %d\r\n", msg.msgid);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Send a heartbeat
|
||||
*/
|
||||
static inline void mavlink_send_heartbeat(void)
|
||||
{
|
||||
mavlink_msg_heartbeat_send(MAVLINK_COMM_0,
|
||||
MAV_TYPE_QUADROTOR,
|
||||
MAV_AUTOPILOT_PPZ,
|
||||
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED,
|
||||
0,
|
||||
MAV_STATE_STANDBY);
|
||||
MAVLink(SendMessage());
|
||||
}
|
||||
|
||||
/**
|
||||
* Send the system status
|
||||
*/
|
||||
static inline void mavlink_send_sys_status(void)
|
||||
{
|
||||
mavlink_msg_sys_status_send(MAVLINK_COMM_0,
|
||||
UAV_SENSORS, // On-board sensors: present (bitmap)
|
||||
UAV_SENSORS, // On-board sensors: active (bitmap)
|
||||
UAV_SENSORS, // On-board sensors: state (bitmap)
|
||||
-1,//10*sys_mon.cpu_load, // System loadof main-loop time (0=0% to 1000=100%)
|
||||
100 * electrical.vsupply, // Battery voltage (milivolts)
|
||||
electrical.current / 10, // Battery current (10x miliampere)
|
||||
-1, // Battery remaining (0-100 in %)
|
||||
0, // Communication packet drops (0=0% to 10000=100%)
|
||||
0, // Communication error(per packet) (0=0% to 10000=100%)
|
||||
0, // Autopilot specific error 1
|
||||
0, // Autopilot specific error 2
|
||||
0, // Autopilot specific error 3
|
||||
0); // Autopilot specific error 4
|
||||
MAVLink(SendMessage());
|
||||
}
|
||||
|
||||
/**
|
||||
* Send the attitude
|
||||
*/
|
||||
static inline void mavlink_send_attitude(void)
|
||||
{
|
||||
mavlink_msg_attitude_send(MAVLINK_COMM_0,
|
||||
get_sys_time_msec(),
|
||||
stateGetNedToBodyEulers_f()->phi, // Phi
|
||||
stateGetNedToBodyEulers_f()->theta, // Theta
|
||||
stateGetNedToBodyEulers_f()->psi, // Psi
|
||||
stateGetBodyRates_f()->p, // p
|
||||
stateGetBodyRates_f()->q, // q
|
||||
stateGetBodyRates_f()->r); // r
|
||||
MAVLink(SendMessage());
|
||||
}
|
||||
|
||||
static inline void mavlink_send_local_position_ned(void)
|
||||
{
|
||||
mavlink_msg_local_position_ned_send(MAVLINK_COMM_0,
|
||||
get_sys_time_msec(),
|
||||
stateGetPositionNed_f()->x,
|
||||
stateGetPositionNed_f()->y,
|
||||
stateGetPositionNed_f()->z,
|
||||
stateGetSpeedNed_f()->x,
|
||||
stateGetSpeedNed_f()->y,
|
||||
stateGetSpeedNed_f()->z);
|
||||
MAVLink(SendMessage());
|
||||
}
|
||||
|
||||
static inline void mavlink_send_global_position_int(void)
|
||||
{
|
||||
float heading = DegOfRad(stateGetNedToBodyEulers_f()->psi);
|
||||
if (heading < 0.) {
|
||||
heading += 360;
|
||||
}
|
||||
uint16_t compass_heading = heading * 100;
|
||||
int32_t relative_alt = stateGetPositionLla_i()->alt - state.ned_origin_f.hmsl;
|
||||
/// TODO: check/ask what coordinate system vel is supposed to be in, not clear from docs
|
||||
mavlink_msg_global_position_int_send(MAVLINK_COMM_0,
|
||||
get_sys_time_msec(),
|
||||
stateGetPositionLla_i()->lat,
|
||||
stateGetPositionLla_i()->lon,
|
||||
stateGetPositionLla_i()->alt,
|
||||
relative_alt,
|
||||
stateGetSpeedNed_f()->x * 100,
|
||||
stateGetSpeedNed_f()->y * 100,
|
||||
stateGetSpeedNed_f()->z * 100,
|
||||
compass_heading);
|
||||
MAVLink(SendMessage());
|
||||
}
|
||||
|
||||
/**
|
||||
* Send the parameters
|
||||
*/
|
||||
static inline void mavlink_send_params(void)
|
||||
{
|
||||
if (mavlink_params_idx >= NB_SETTING) {
|
||||
return;
|
||||
}
|
||||
|
||||
mavlink_msg_param_value_send(MAVLINK_COMM_0,
|
||||
mavlink_params[mavlink_params_idx],
|
||||
settings_get_value(mavlink_params_idx),
|
||||
MAV_PARAM_TYPE_REAL32,
|
||||
NB_SETTING,
|
||||
mavlink_params_idx);
|
||||
MAVLink(SendMessage());
|
||||
|
||||
mavlink_params_idx++;
|
||||
}
|
||||
|
||||
static inline void mavlink_send_autopilot_version(void)
|
||||
{
|
||||
/// TODO: fill in versions correctly, how should they be encoded?
|
||||
static uint8_t custom_version[8];
|
||||
mavlink_msg_autopilot_version_send(MAVLINK_COMM_0,
|
||||
0, // capabilities,
|
||||
54, // version
|
||||
custom_version);
|
||||
}
|
||||
|
||||
static inline void mavlink_send_attitude_quaternion(void)
|
||||
{
|
||||
/// TODO: check if same quaternion rotation or inverse
|
||||
mavlink_msg_attitude_quaternion_send(MAVLINK_COMM_0,
|
||||
get_sys_time_msec(),
|
||||
stateGetNedToBodyQuat_f()->qi,
|
||||
stateGetNedToBodyQuat_f()->qx,
|
||||
stateGetNedToBodyQuat_f()->qy,
|
||||
stateGetNedToBodyQuat_f()->qz,
|
||||
stateGetBodyRates_f()->p,
|
||||
stateGetBodyRates_f()->q,
|
||||
stateGetBodyRates_f()->r);
|
||||
}
|
||||
|
||||
#if USE_GPS
|
||||
#include "subsystems/gps.h"
|
||||
#endif
|
||||
|
||||
static inline void mavlink_send_gps_raw_int(void)
|
||||
{
|
||||
#if USE_GPS
|
||||
int32_t course = DegOfRad(gps.course) / 1e5;
|
||||
if (course < 0) {
|
||||
course += 36000;
|
||||
}
|
||||
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
|
||||
get_sys_time_usec(),
|
||||
gps.fix,
|
||||
gps.lla_pos.lat,
|
||||
gps.lla_pos.lon,
|
||||
gps.lla_pos.alt,
|
||||
gps.pdop,
|
||||
UINT16_MAX, // VDOP
|
||||
gps.gspeed,
|
||||
course,
|
||||
gps.num_sv);
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined RADIO_CONTROL
|
||||
#include "subsystems/radio_control.h"
|
||||
// since they really want PPM values, use a hack to check if are using ppm subsystem
|
||||
#ifdef PPM_PULSE_TYPE_POSITIVE
|
||||
#define RC_CHANNELS RADIO_CTL_NB
|
||||
/// macro to get ppm_pulses or UINT16_MAX if channel not available
|
||||
#define PPM_PULSES(_i) ((_i) < RADIO_CTL_NB ? ppm_pulses[(_i)] : UINT16_MAX)
|
||||
#else
|
||||
// use radio_control.values for now...
|
||||
#define RC_CHANNELS RADIO_CONTROL_NB_CHANNEL
|
||||
#define PPM_OF_PPRZ(_v) ((_v) / 19.2 + 1500)
|
||||
#define PPM_PULSES(_i) ((_i) < RADIO_CONTROL_NB_CHANNEL ? PPM_OF_PPRZ(radio_control.values[(_i)]) + MAX_PPRZ : UINT16_MAX)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
static inline void mavlink_send_rc_channels(void)
|
||||
{
|
||||
#if defined RADIO_CONTROL
|
||||
mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
|
||||
get_sys_time_msec(),
|
||||
RC_CHANNELS,
|
||||
PPM_PULSES(0), PPM_PULSES(1), PPM_PULSES(2),
|
||||
PPM_PULSES(3), PPM_PULSES(4), PPM_PULSES(5),
|
||||
PPM_PULSES(6), PPM_PULSES(7), PPM_PULSES(8),
|
||||
PPM_PULSES(9), PPM_PULSES(10), PPM_PULSES(11),
|
||||
PPM_PULSES(12), PPM_PULSES(13), PPM_PULSES(14),
|
||||
PPM_PULSES(15), PPM_PULSES(16), PPM_PULSES(17),
|
||||
255); // rssi unknown
|
||||
#else
|
||||
mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
|
||||
get_sys_time_msec(),
|
||||
0, // zero channels available
|
||||
UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
|
||||
UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
|
||||
UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
|
||||
UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
|
||||
UINT16_MAX, UINT16_MAX, 255);
|
||||
#endif
|
||||
}
|
||||
|
||||
#include "subsystems/electrical.h"
|
||||
static inline void mavlink_send_battery_status(void)
|
||||
{
|
||||
static uint16_t voltages[10];
|
||||
// we simply only set one cell for now
|
||||
voltages[0] = electrical.vsupply * 10;
|
||||
/// TODO: check what all these fields are supposed to represent
|
||||
mavlink_msg_battery_status_send(MAVLINK_COMM_0,
|
||||
0, // id
|
||||
0, // battery_function
|
||||
0, // type
|
||||
INT16_MAX, // unknown temperature
|
||||
voltages, // cell voltages
|
||||
electrical.current / 10,
|
||||
electrical.consumed,
|
||||
electrical.energy, // check scaling
|
||||
-1); // remaining percentage not estimated
|
||||
}
|
||||
@@ -0,0 +1,78 @@
|
||||
/*
|
||||
* Copyright (C) 2014 Freek van Tienen <freek.v.tienen@gmail.com>
|
||||
*
|
||||
* This file is part of paparazzi.
|
||||
*
|
||||
* paparazzi is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 2, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* paparazzi is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with paparazzi; see the file COPYING. If not, write to
|
||||
* the Free Software Foundation, 59 Temple Place - Suite 330,
|
||||
* Boston, MA 02111-1307, USA.
|
||||
*
|
||||
*/
|
||||
|
||||
/** @file modules/datalink/mavlink.h
|
||||
* @brief Basic MAVLink datalink implementation
|
||||
*/
|
||||
|
||||
#ifndef DATALINK_MAVLINK_H
|
||||
#define DATALINK_MAVLINK_H
|
||||
|
||||
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
#define MAVLINK_ALIGNED_FIELDS 0
|
||||
|
||||
#include <mavlink/mavlink_types.h>
|
||||
|
||||
#if USE_UDP
|
||||
#include "mcu_periph/udp.h"
|
||||
#endif
|
||||
#if USE_USB_SERIAL
|
||||
#include "mcu_periph/usb_serial.h"
|
||||
#endif
|
||||
#include "mcu_periph/uart.h"
|
||||
|
||||
/*
|
||||
* MAVLink description before main MAVLink include
|
||||
*/
|
||||
extern mavlink_system_t mavlink_system;
|
||||
|
||||
#ifndef MAVLINK_DEV
|
||||
#define MAVLINK_DEV UART1
|
||||
#endif
|
||||
|
||||
/*
|
||||
* The MAVLink link description
|
||||
*/
|
||||
#define __MAVLink(dev, _x) dev##_x
|
||||
#define _MAVLink(dev, _x) __MAVLink(dev, _x)
|
||||
#define MAVLink(_x) _MAVLink(MAVLINK_DEV, _x)
|
||||
|
||||
/**
|
||||
* Module functions
|
||||
*/
|
||||
void mavlink_init(void);
|
||||
void mavlink_periodic(void);
|
||||
void mavlink_event(void);
|
||||
|
||||
/**
|
||||
* @brief Send one char (uint8_t) over a comm channel
|
||||
*
|
||||
* @param chan MAVLink channel to use, usually MAVLINK_COMM_0 = UART0
|
||||
* @param ch Character to send
|
||||
*/
|
||||
static inline void comm_send_ch(mavlink_channel_t chan __attribute__((unused)), uint8_t ch)
|
||||
{
|
||||
// Send bytes
|
||||
MAVLink(Transmit(ch));
|
||||
}
|
||||
|
||||
#endif // DATALINK_MAVLINK_H
|
||||
@@ -0,0 +1,90 @@
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#ifndef _CHECKSUM_H_
|
||||
#define _CHECKSUM_H_
|
||||
|
||||
|
||||
/**
|
||||
*
|
||||
* 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
|
||||
File diff suppressed because one or more lines are too long
@@ -0,0 +1,27 @@
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol built from common.xml
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
*/
|
||||
#ifndef MAVLINK_H
|
||||
#define MAVLINK_H
|
||||
|
||||
#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
|
||||
|
||||
#include "version.h"
|
||||
#include "common.h"
|
||||
|
||||
#endif // MAVLINK_H
|
||||
@@ -0,0 +1,353 @@
|
||||
// MESSAGE ATTITUDE PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE 30
|
||||
|
||||
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_30_LEN 28
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE_CRC 39
|
||||
#define MAVLINK_MSG_ID_30_CRC 39
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_attitude_t packet;
|
||||
packet.time_boot_ms = time_boot_ms;
|
||||
packet.roll = roll;
|
||||
packet.pitch = pitch;
|
||||
packet.yaw = yaw;
|
||||
packet.rollspeed = rollspeed;
|
||||
packet.pitchspeed = pitchspeed;
|
||||
packet.yawspeed = yawspeed;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_attitude_t *packet = (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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(attitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,377 @@
|
||||
// MESSAGE ATTITUDE_QUATERNION PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31
|
||||
|
||||
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_31_LEN 32
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246
|
||||
#define MAVLINK_MSG_ID_31_CRC 246
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_attitude_quaternion_t packet;
|
||||
packet.time_boot_ms = time_boot_ms;
|
||||
packet.q1 = q1;
|
||||
packet.q2 = q2;
|
||||
packet.q3 = q3;
|
||||
packet.q4 = q4;
|
||||
packet.rollspeed = rollspeed;
|
||||
packet.pitchspeed = pitchspeed;
|
||||
packet.yawspeed = yawspeed;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_attitude_quaternion_t *packet = (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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,322 @@
|
||||
// MESSAGE ATTITUDE_QUATERNION_COV PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61
|
||||
|
||||
typedef struct __mavlink_attitude_quaternion_cov_t
|
||||
{
|
||||
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
|
||||
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 68
|
||||
#define MAVLINK_MSG_ID_61_LEN 68
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC 153
|
||||
#define MAVLINK_MSG_ID_61_CRC 153
|
||||
|
||||
#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN 4
|
||||
#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN 9
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \
|
||||
"ATTITUDE_QUATERNION_COV", \
|
||||
6, \
|
||||
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_boot_ms) }, \
|
||||
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \
|
||||
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \
|
||||
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \
|
||||
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \
|
||||
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 32, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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_boot_ms Timestamp (milliseconds since system boot)
|
||||
* @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,
|
||||
uint32_t time_boot_ms, 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_uint32_t(buf, 0, time_boot_ms);
|
||||
_mav_put_float(buf, 20, rollspeed);
|
||||
_mav_put_float(buf, 24, pitchspeed);
|
||||
_mav_put_float(buf, 28, yawspeed);
|
||||
_mav_put_float_array(buf, 4, q, 4);
|
||||
_mav_put_float_array(buf, 32, 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_boot_ms = time_boot_ms;
|
||||
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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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_boot_ms Timestamp (milliseconds since system boot)
|
||||
* @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,
|
||||
uint32_t time_boot_ms,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_uint32_t(buf, 0, time_boot_ms);
|
||||
_mav_put_float(buf, 20, rollspeed);
|
||||
_mav_put_float(buf, 24, pitchspeed);
|
||||
_mav_put_float(buf, 28, yawspeed);
|
||||
_mav_put_float_array(buf, 4, q, 4);
|
||||
_mav_put_float_array(buf, 32, 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_boot_ms = time_boot_ms;
|
||||
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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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_boot_ms, 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_boot_ms, 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_boot_ms Timestamp (milliseconds since system boot)
|
||||
* @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, uint32_t time_boot_ms, 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_uint32_t(buf, 0, time_boot_ms);
|
||||
_mav_put_float(buf, 20, rollspeed);
|
||||
_mav_put_float(buf, 24, pitchspeed);
|
||||
_mav_put_float(buf, 28, yawspeed);
|
||||
_mav_put_float_array(buf, 4, q, 4);
|
||||
_mav_put_float_array(buf, 32, covariance, 9);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_attitude_quaternion_cov_t packet;
|
||||
packet.time_boot_ms = time_boot_ms;
|
||||
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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
|
||||
#endif
|
||||
#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, uint32_t time_boot_ms, 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_uint32_t(buf, 0, time_boot_ms);
|
||||
_mav_put_float(buf, 20, rollspeed);
|
||||
_mav_put_float(buf, 24, pitchspeed);
|
||||
_mav_put_float(buf, 28, yawspeed);
|
||||
_mav_put_float_array(buf, 4, q, 4);
|
||||
_mav_put_float_array(buf, 32, covariance, 9);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_attitude_quaternion_cov_t *packet = (mavlink_attitude_quaternion_cov_t *)msgbuf;
|
||||
packet->time_boot_ms = time_boot_ms;
|
||||
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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE ATTITUDE_QUATERNION_COV UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field time_boot_ms from attitude_quaternion_cov message
|
||||
*
|
||||
* @return Timestamp (milliseconds since system boot)
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint32_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, 4);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 28);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 32);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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
|
||||
attitude_quaternion_cov->time_boot_ms = mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(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
|
||||
memcpy(attitude_quaternion_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,345 @@
|
||||
// MESSAGE ATTITUDE_TARGET PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE_TARGET 83
|
||||
|
||||
typedef struct __mavlink_attitude_target_t
|
||||
{
|
||||
uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
|
||||
float q[4]; ///< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
|
||||
float body_roll_rate; ///< Body roll rate in radians per second
|
||||
float body_pitch_rate; ///< Body roll rate in radians per second
|
||||
float body_yaw_rate; ///< Body roll rate in radians per second
|
||||
float thrust; ///< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
|
||||
uint8_t type_mask; ///< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
|
||||
} mavlink_attitude_target_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37
|
||||
#define MAVLINK_MSG_ID_83_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
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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 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_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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 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_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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 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_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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
|
||||
#endif
|
||||
#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 roll 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 roll 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
|
||||
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
|
||||
memcpy(attitude_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,209 @@
|
||||
// MESSAGE AUTH_KEY PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_AUTH_KEY 7
|
||||
|
||||
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_7_LEN 32
|
||||
|
||||
#define MAVLINK_MSG_ID_AUTH_KEY_CRC 119
|
||||
#define MAVLINK_MSG_ID_7_CRC 119
|
||||
|
||||
#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \
|
||||
"AUTH_KEY", \
|
||||
1, \
|
||||
{ { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_auth_key_t packet;
|
||||
|
||||
mav_array_memcpy(packet.key, key, sizeof(char)*32);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf;
|
||||
|
||||
mav_array_memcpy(packet->key, key, sizeof(char)*32);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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_msg_auth_key_get_key(msg, auth_key->key);
|
||||
#else
|
||||
memcpy(auth_key, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,249 @@
|
||||
// MESSAGE AUTOPILOT_VERSION PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148
|
||||
|
||||
typedef struct __mavlink_autopilot_version_t
|
||||
{
|
||||
uint64_t capabilities; ///< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
|
||||
uint32_t version; ///< Firmware version number
|
||||
uint8_t custom_version[8]; ///< Custom version field, commonly the first 8 bytes (16 characters) 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 20
|
||||
#define MAVLINK_MSG_ID_148_LEN 20
|
||||
|
||||
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 49
|
||||
#define MAVLINK_MSG_ID_148_CRC 49
|
||||
|
||||
#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_CUSTOM_VERSION_LEN 8
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \
|
||||
"AUTOPILOT_VERSION", \
|
||||
3, \
|
||||
{ { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \
|
||||
{ "version", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_autopilot_version_t, version) }, \
|
||||
{ "custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 12, offsetof(mavlink_autopilot_version_t, custom_version) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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 version Firmware version number
|
||||
* @param custom_version Custom version field, commonly the first 8 bytes (16 characters) of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
|
||||
* @return 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 version, const uint8_t *custom_version)
|
||||
{
|
||||
#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_uint32_t(buf, 8, version);
|
||||
_mav_put_uint8_t_array(buf, 12, 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.version = version;
|
||||
mav_array_memcpy(packet.custom_version, 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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 version Firmware version number
|
||||
* @param custom_version Custom version field, commonly the first 8 bytes (16 characters) of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
|
||||
* @return 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 version,const uint8_t *custom_version)
|
||||
{
|
||||
#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_uint32_t(buf, 8, version);
|
||||
_mav_put_uint8_t_array(buf, 12, 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.version = version;
|
||||
mav_array_memcpy(packet.custom_version, 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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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->version, autopilot_version->custom_version);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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->version, autopilot_version->custom_version);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 version Firmware version number
|
||||
* @param custom_version Custom version field, commonly the first 8 bytes (16 characters) 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.
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, uint64_t capabilities, uint32_t version, const uint8_t *custom_version)
|
||||
{
|
||||
#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_uint32_t(buf, 8, version);
|
||||
_mav_put_uint8_t_array(buf, 12, custom_version, 8);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_autopilot_version_t packet;
|
||||
packet.capabilities = capabilities;
|
||||
packet.version = version;
|
||||
mav_array_memcpy(packet.custom_version, custom_version, sizeof(uint8_t)*8);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
|
||||
#endif
|
||||
#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 version, const uint8_t *custom_version)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
_mav_put_uint64_t(buf, 0, capabilities);
|
||||
_mav_put_uint32_t(buf, 8, version);
|
||||
_mav_put_uint8_t_array(buf, 12, custom_version, 8);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf;
|
||||
packet->capabilities = capabilities;
|
||||
packet->version = version;
|
||||
mav_array_memcpy(packet->custom_version, custom_version, sizeof(uint8_t)*8);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
|
||||
#endif
|
||||
#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 version from autopilot_version message
|
||||
*
|
||||
* @return Firmware version number
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_autopilot_version_get_version(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint32_t(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field custom_version from autopilot_version message
|
||||
*
|
||||
* @return Custom version field, commonly the first 8 bytes (16 characters) 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_custom_version(const mavlink_message_t* msg, uint8_t *custom_version)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t_array(msg, custom_version, 8, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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
|
||||
autopilot_version->capabilities = mavlink_msg_autopilot_version_get_capabilities(msg);
|
||||
autopilot_version->version = mavlink_msg_autopilot_version_get_version(msg);
|
||||
mavlink_msg_autopilot_version_get_custom_version(msg, autopilot_version->custom_version);
|
||||
#else
|
||||
memcpy(autopilot_version, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,393 @@
|
||||
// MESSAGE BATTERY_STATUS PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_BATTERY_STATUS 147
|
||||
|
||||
typedef struct __mavlink_battery_status_t
|
||||
{
|
||||
int32_t current_consumed; ///< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
|
||||
int32_t energy_consumed; ///< Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
|
||||
int16_t temperature; ///< Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
|
||||
uint16_t voltages[10]; ///< Battery voltage of cells, in millivolts (1 = 1 millivolt)
|
||||
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_147_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
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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)
|
||||
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
|
||||
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
|
||||
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
|
||||
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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)
|
||||
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
|
||||
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
|
||||
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
|
||||
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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)
|
||||
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
|
||||
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
|
||||
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
|
||||
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
|
||||
*/
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_battery_status_t packet;
|
||||
packet.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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_battery_status_t *packet = (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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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)
|
||||
*/
|
||||
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 100*Joules (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
|
||||
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
|
||||
memcpy(battery_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,273 @@
|
||||
// MESSAGE CHANGE_OPERATOR_CONTROL PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5
|
||||
|
||||
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_5_LEN 28
|
||||
|
||||
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC 217
|
||||
#define MAVLINK_MSG_ID_5_CRC 217
|
||||
|
||||
#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \
|
||||
"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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_change_operator_control_t packet;
|
||||
packet.target_system = target_system;
|
||||
packet.control_request = control_request;
|
||||
packet.version = version;
|
||||
mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_change_operator_control_t *packet = (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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(change_operator_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,257 @@
|
||||
// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6
|
||||
|
||||
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_6_LEN 3
|
||||
|
||||
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104
|
||||
#define MAVLINK_MSG_ID_6_CRC 104
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \
|
||||
"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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_change_operator_control_ack_t packet;
|
||||
packet.gcs_system_id = gcs_system_id;
|
||||
packet.control_request = control_request;
|
||||
packet.ack = ack;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_change_operator_control_ack_t *packet = (mavlink_change_operator_control_ack_t *)msgbuf;
|
||||
packet->gcs_system_id = gcs_system_id;
|
||||
packet->control_request = control_request;
|
||||
packet->ack = ack;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,233 @@
|
||||
// MESSAGE COMMAND_ACK PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_ACK 77
|
||||
|
||||
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_77_LEN 3
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143
|
||||
#define MAVLINK_MSG_ID_77_CRC 143
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_command_ack_t packet;
|
||||
packet.command = command;
|
||||
packet.result = result;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf;
|
||||
packet->command = command;
|
||||
packet->result = result;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
command_ack->command = mavlink_msg_command_ack_get_command(msg);
|
||||
command_ack->result = mavlink_msg_command_ack_get_result(msg);
|
||||
#else
|
||||
memcpy(command_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_ACK_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,497 @@
|
||||
// MESSAGE COMMAND_INT PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_INT 75
|
||||
|
||||
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_75_LEN 35
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_INT_CRC 158
|
||||
#define MAVLINK_MSG_ID_75_CRC 158
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_LEN);
|
||||
#endif
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_LEN);
|
||||
#endif
|
||||
#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
|
||||
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
|
||||
memcpy(command_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_INT_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,449 @@
|
||||
// MESSAGE COMMAND_LONG PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_LONG 76
|
||||
|
||||
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_76_LEN 33
|
||||
|
||||
#define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152
|
||||
#define MAVLINK_MSG_ID_76_CRC 152
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_command_long_t packet;
|
||||
packet.param1 = param1;
|
||||
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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_command_long_t *packet = (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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(command_long, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_LONG_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,257 @@
|
||||
// MESSAGE DATA_STREAM PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA_STREAM 67
|
||||
|
||||
typedef struct __mavlink_data_stream_t
|
||||
{
|
||||
uint16_t message_rate; ///< The requested interval between two messages of this type
|
||||
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_67_LEN 4
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA_STREAM_CRC 21
|
||||
#define MAVLINK_MSG_ID_67_CRC 21
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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 requested interval between two messages of this type
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 requested interval between two messages of this type
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 requested interval between two messages of this type
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_data_stream_t packet;
|
||||
packet.message_rate = message_rate;
|
||||
packet.stream_id = stream_id;
|
||||
packet.on_off = on_off;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_data_stream_t *packet = (mavlink_data_stream_t *)msgbuf;
|
||||
packet->message_rate = message_rate;
|
||||
packet->stream_id = stream_id;
|
||||
packet->on_off = on_off;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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 requested interval between two messages of this type
|
||||
*/
|
||||
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
|
||||
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
|
||||
memcpy(data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_STREAM_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,353 @@
|
||||
// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130
|
||||
|
||||
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_130_LEN 13
|
||||
|
||||
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29
|
||||
#define MAVLINK_MSG_ID_130_CRC 29
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_data_transmission_handshake_t packet;
|
||||
packet.size = size;
|
||||
packet.width = width;
|
||||
packet.height = height;
|
||||
packet.packets = packets;
|
||||
packet.type = type;
|
||||
packet.payload = payload;
|
||||
packet.jpg_quality = jpg_quality;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_data_transmission_handshake_t *packet = (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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,257 @@
|
||||
// MESSAGE DEBUG PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_DEBUG 254
|
||||
|
||||
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_254_LEN 9
|
||||
|
||||
#define MAVLINK_MSG_ID_DEBUG_CRC 46
|
||||
#define MAVLINK_MSG_ID_254_CRC 46
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_debug_t packet;
|
||||
packet.time_boot_ms = time_boot_ms;
|
||||
packet.value = value;
|
||||
packet.ind = ind;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_debug_t *packet = (mavlink_debug_t *)msgbuf;
|
||||
packet->time_boot_ms = time_boot_ms;
|
||||
packet->value = value;
|
||||
packet->ind = ind;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(debug, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,297 @@
|
||||
// MESSAGE DEBUG_VECT PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_DEBUG_VECT 250
|
||||
|
||||
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_250_LEN 30
|
||||
|
||||
#define MAVLINK_MSG_ID_DEBUG_VECT_CRC 49
|
||||
#define MAVLINK_MSG_ID_250_CRC 49
|
||||
|
||||
#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
|
||||
"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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_debug_vect_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
packet.x = x;
|
||||
packet.y = y;
|
||||
packet.z = z;
|
||||
mav_array_memcpy(packet.name, name, sizeof(char)*10);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_debug_vect_t *packet = (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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(debug_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_VECT_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,377 @@
|
||||
// MESSAGE DISTANCE_SENSOR PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_DISTANCE_SENSOR 132
|
||||
|
||||
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 FIXME 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_132_LEN 14
|
||||
|
||||
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85
|
||||
#define MAVLINK_MSG_ID_132_CRC 85
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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 FIXME 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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 FIXME 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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 FIXME 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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
|
||||
#endif
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
|
||||
#endif
|
||||
#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 FIXME 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
|
||||
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
|
||||
memcpy(distance_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,225 @@
|
||||
// MESSAGE ENCAPSULATED_DATA PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 131
|
||||
|
||||
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_131_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
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_encapsulated_data_t packet;
|
||||
packet.seqnr = seqnr;
|
||||
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_encapsulated_data_t *packet = (mavlink_encapsulated_data_t *)msgbuf;
|
||||
packet->seqnr = seqnr;
|
||||
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*253);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg);
|
||||
mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data);
|
||||
#else
|
||||
memcpy(encapsulated_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,273 @@
|
||||
// MESSAGE FILE_TRANSFER_PROTOCOL PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 110
|
||||
|
||||
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_110_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
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
|
||||
#endif
|
||||
#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
|
||||
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
|
||||
memcpy(file_transfer_protocol, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,401 @@
|
||||
// MESSAGE GLOBAL_POSITION_INT PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33
|
||||
|
||||
typedef struct __mavlink_global_position_int_t
|
||||
{
|
||||
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
|
||||
int32_t lat; ///< Latitude, expressed as * 1E7
|
||||
int32_t lon; ///< Longitude, expressed as * 1E7
|
||||
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
|
||||
int32_t relative_alt; ///< Altitude above ground in meters, expressed as * 1000 (millimeters)
|
||||
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
|
||||
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
|
||||
int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
|
||||
uint16_t hdg; ///< Compass heading 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_33_LEN 28
|
||||
|
||||
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104
|
||||
#define MAVLINK_MSG_ID_33_CRC 104
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
|
||||
"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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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 * 1E7
|
||||
* @param lon Longitude, expressed as * 1E7
|
||||
* @param alt Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
|
||||
* @param relative_alt Altitude above ground 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 hdg Compass heading 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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 * 1E7
|
||||
* @param lon Longitude, expressed as * 1E7
|
||||
* @param alt Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
|
||||
* @param relative_alt Altitude above ground 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 hdg Compass heading 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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 * 1E7
|
||||
* @param lon Longitude, expressed as * 1E7
|
||||
* @param alt Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
|
||||
* @param relative_alt Altitude above ground 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 hdg Compass heading 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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_global_position_int_t packet;
|
||||
packet.time_boot_ms = time_boot_ms;
|
||||
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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_global_position_int_t *packet = (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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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 * 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 * 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), WGS84 (not AMSL)
|
||||
*/
|
||||
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), 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), 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), 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 Compass heading 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
|
||||
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
|
||||
memcpy(global_position_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,441 @@
|
||||
// MESSAGE GLOBAL_POSITION_INT_COV PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63
|
||||
|
||||
typedef struct __mavlink_global_position_int_cov_t
|
||||
{
|
||||
uint64_t time_utc; ///< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
||||
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), 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 185
|
||||
#define MAVLINK_MSG_ID_63_LEN 185
|
||||
|
||||
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 51
|
||||
#define MAVLINK_MSG_ID_63_CRC 51
|
||||
|
||||
#define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \
|
||||
"GLOBAL_POSITION_INT_COV", \
|
||||
11, \
|
||||
{ { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_utc) }, \
|
||||
{ "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, time_boot_ms) }, \
|
||||
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lat) }, \
|
||||
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, lon) }, \
|
||||
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, alt) }, \
|
||||
{ "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \
|
||||
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vx) }, \
|
||||
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vy) }, \
|
||||
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_int_cov_t, vz) }, \
|
||||
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 40, offsetof(mavlink_global_position_int_cov_t, covariance) }, \
|
||||
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 184, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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_boot_ms Timestamp (milliseconds since system boot)
|
||||
* @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
||||
* @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,
|
||||
uint32_t time_boot_ms, uint64_t time_utc, 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_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_float(buf, 28, vx);
|
||||
_mav_put_float(buf, 32, vy);
|
||||
_mav_put_float(buf, 36, vz);
|
||||
_mav_put_uint8_t(buf, 184, estimator_type);
|
||||
_mav_put_float_array(buf, 40, 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_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.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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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_boot_ms Timestamp (milliseconds since system boot)
|
||||
* @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
||||
* @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,
|
||||
uint32_t time_boot_ms,uint64_t time_utc,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_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_float(buf, 28, vx);
|
||||
_mav_put_float(buf, 32, vy);
|
||||
_mav_put_float(buf, 36, vz);
|
||||
_mav_put_uint8_t(buf, 184, estimator_type);
|
||||
_mav_put_float_array(buf, 40, 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_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.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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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_boot_ms, global_position_int_cov->time_utc, 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_boot_ms, global_position_int_cov->time_utc, 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_boot_ms Timestamp (milliseconds since system boot)
|
||||
* @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
||||
* @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, uint32_t time_boot_ms, uint64_t time_utc, 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_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_float(buf, 28, vx);
|
||||
_mav_put_float(buf, 32, vy);
|
||||
_mav_put_float(buf, 36, vz);
|
||||
_mav_put_uint8_t(buf, 184, estimator_type);
|
||||
_mav_put_float_array(buf, 40, covariance, 36);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_global_position_int_cov_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.vx = vx;
|
||||
packet.vy = vy;
|
||||
packet.vz = vz;
|
||||
packet.estimator_type = estimator_type;
|
||||
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
||||
#endif
|
||||
#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, uint32_t time_boot_ms, uint64_t time_utc, 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_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_float(buf, 28, vx);
|
||||
_mav_put_float(buf, 32, vy);
|
||||
_mav_put_float(buf, 36, vz);
|
||||
_mav_put_uint8_t(buf, 184, estimator_type);
|
||||
_mav_put_float_array(buf, 40, covariance, 36);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_global_position_int_cov_t *packet = (mavlink_global_position_int_cov_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->vx = vx;
|
||||
packet->vy = vy;
|
||||
packet->vz = vz;
|
||||
packet->estimator_type = estimator_type;
|
||||
mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE GLOBAL_POSITION_INT_COV UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field time_boot_ms from global_position_int_cov message
|
||||
*
|
||||
* @return Timestamp (milliseconds since system boot)
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_global_position_int_cov_get_time_boot_ms(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint32_t(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field time_utc from global_position_int_cov message
|
||||
*
|
||||
* @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
||||
*/
|
||||
static inline uint64_t mavlink_msg_global_position_int_cov_get_time_utc(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, 184);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 28);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 32);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 36);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 40);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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
|
||||
global_position_int_cov->time_utc = mavlink_msg_global_position_int_cov_get_time_utc(msg);
|
||||
global_position_int_cov->time_boot_ms = mavlink_msg_global_position_int_cov_get_time_boot_ms(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
|
||||
memcpy(global_position_int_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,353 @@
|
||||
// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101
|
||||
|
||||
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_101_LEN 32
|
||||
|
||||
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102
|
||||
#define MAVLINK_MSG_ID_101_CRC 102
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \
|
||||
"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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_global_vision_position_estimate_t packet;
|
||||
packet.usec = usec;
|
||||
packet.x = x;
|
||||
packet.y = y;
|
||||
packet.z = z;
|
||||
packet.roll = roll;
|
||||
packet.pitch = pitch;
|
||||
packet.yaw = yaw;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_global_vision_position_estimate_t *packet = (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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,473 @@
|
||||
// MESSAGE GPS2_RAW PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS2_RAW 124
|
||||
|
||||
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 (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; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK 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
|
||||
uint8_t dgps_numch; ///< Number of DGPS satellites
|
||||
} mavlink_gps2_raw_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35
|
||||
#define MAVLINK_MSG_ID_124_LEN 35
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS2_RAW_CRC 87
|
||||
#define MAVLINK_MSG_ID_124_CRC 87
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK 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 (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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK 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 (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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK 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 (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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
#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 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK 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_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 (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
|
||||
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
|
||||
memcpy(gps2_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RAW_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,497 @@
|
||||
// MESSAGE GPS2_RTK PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS2_RTK 128
|
||||
|
||||
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_128_LEN 35
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS2_RTK_CRC 226
|
||||
#define MAVLINK_MSG_ID_128_CRC 226
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
||||
#endif
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
||||
#endif
|
||||
#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
|
||||
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
|
||||
memcpy(gps2_rtk, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RTK_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,257 @@
|
||||
// MESSAGE GPS_GLOBAL_ORIGIN PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49
|
||||
|
||||
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 (WGS84), in meters * 1000 (positive for up)
|
||||
} mavlink_gps_global_origin_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12
|
||||
#define MAVLINK_MSG_ID_49_LEN 12
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39
|
||||
#define MAVLINK_MSG_ID_49_CRC 39
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \
|
||||
"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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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 (WGS84), in meters * 1000 (positive for up)
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
int32_t latitude, int32_t longitude, int32_t altitude)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 (WGS84), in meters * 1000 (positive for up)
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 (WGS84), in meters * 1000 (positive for up)
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_gps_global_origin_t packet;
|
||||
packet.latitude = latitude;
|
||||
packet.longitude = longitude;
|
||||
packet.altitude = altitude;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_gps_global_origin_t *packet = (mavlink_gps_global_origin_t *)msgbuf;
|
||||
packet->latitude = latitude;
|
||||
packet->longitude = longitude;
|
||||
packet->altitude = altitude;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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 (WGS84), 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
|
||||
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
|
||||
memcpy(gps_global_origin, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,273 @@
|
||||
// MESSAGE GPS_INJECT_DATA PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_INJECT_DATA 123
|
||||
|
||||
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_123_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
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
#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
|
||||
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
|
||||
memcpy(gps_inject_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,425 @@
|
||||
// MESSAGE GPS_RAW_INT PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_RAW_INT 24
|
||||
|
||||
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 (WGS84), in meters * 1000 (positive for up)
|
||||
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; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. 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_gps_raw_int_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
|
||||
#define MAVLINK_MSG_ID_24_LEN 30
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24
|
||||
#define MAVLINK_MSG_ID_24_CRC 24
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
|
||||
"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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. 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 (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
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. 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 (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
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. 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 (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
|
||||
*/
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_gps_raw_int_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_gps_raw_int_t *packet = (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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. 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_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 (WGS84), in meters * 1000 (positive for up)
|
||||
*/
|
||||
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 in cm (m*100). 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 in cm (m*100). 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
|
||||
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
|
||||
memcpy(gps_raw_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,497 @@
|
||||
// MESSAGE GPS_RTK PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_RTK 127
|
||||
|
||||
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_127_LEN 35
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_RTK_CRC 25
|
||||
#define MAVLINK_MSG_ID_127_CRC 25
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_LEN);
|
||||
#endif
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_LEN);
|
||||
#endif
|
||||
#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
|
||||
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
|
||||
memcpy(gps_rtk, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_RTK_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,325 @@
|
||||
// MESSAGE GPS_STATUS PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_STATUS 25
|
||||
|
||||
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_25_LEN 101
|
||||
|
||||
#define MAVLINK_MSG_ID_GPS_STATUS_CRC 23
|
||||
#define MAVLINK_MSG_ID_25_CRC 23
|
||||
|
||||
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
|
||||
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
|
||||
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20
|
||||
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20
|
||||
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_gps_status_t packet;
|
||||
packet.satellites_visible = satellites_visible;
|
||||
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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_gps_status_t *packet = (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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(gps_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_STATUS_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,326 @@
|
||||
// MESSAGE HEARTBEAT PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_HEARTBEAT 0
|
||||
|
||||
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_0_LEN 9
|
||||
|
||||
#define MAVLINK_MSG_ID_HEARTBEAT_CRC 50
|
||||
#define MAVLINK_MSG_ID_0_CRC 50
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_heartbeat_t packet;
|
||||
packet.custom_mode = custom_mode;
|
||||
packet.type = type;
|
||||
packet.autopilot = autopilot;
|
||||
packet.base_mode = base_mode;
|
||||
packet.system_status = system_status;
|
||||
packet.mavlink_version = 3;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_heartbeat_t *packet = (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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(heartbeat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HEARTBEAT_LEN);
|
||||
#endif
|
||||
}
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,449 @@
|
||||
// MESSAGE HIL_CONTROLS PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_CONTROLS 91
|
||||
|
||||
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_91_LEN 42
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63
|
||||
#define MAVLINK_MSG_ID_91_CRC 63
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_hil_controls_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_hil_controls_t *packet = (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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(hil_controls, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,497 @@
|
||||
// MESSAGE HIL_GPS PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_GPS 113
|
||||
|
||||
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 (WGS84), in meters * 1000 (positive for up)
|
||||
uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
|
||||
uint16_t epv; ///< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535
|
||||
uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535
|
||||
int16_t vn; ///< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
|
||||
int16_t ve; ///< GPS velocity in cm/s in EAST direction in earth-fixed NED frame
|
||||
int16_t vd; ///< GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
|
||||
uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
|
||||
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
|
||||
uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255
|
||||
} mavlink_hil_gps_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_GPS_LEN 36
|
||||
#define MAVLINK_MSG_ID_113_LEN 36
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_GPS_CRC 124
|
||||
#define MAVLINK_MSG_ID_113_CRC 124
|
||||
|
||||
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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 (WGS84), in meters * 1000 (positive for up)
|
||||
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
|
||||
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535
|
||||
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
|
||||
* @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
|
||||
* @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame
|
||||
* @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
|
||||
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
|
||||
* @param satellites_visible Number of satellites visible. If unknown, set to 255
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 (WGS84), in meters * 1000 (positive for up)
|
||||
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
|
||||
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535
|
||||
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
|
||||
* @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
|
||||
* @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame
|
||||
* @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
|
||||
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
|
||||
* @param satellites_visible Number of satellites visible. If unknown, set to 255
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 (WGS84), in meters * 1000 (positive for up)
|
||||
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
|
||||
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535
|
||||
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
|
||||
* @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
|
||||
* @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame
|
||||
* @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
|
||||
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
|
||||
* @param satellites_visible Number of satellites visible. If unknown, set to 255
|
||||
*/
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
|
||||
#endif
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
|
||||
#endif
|
||||
#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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
|
||||
#endif
|
||||
#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 (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 (m/s * 100). 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
|
||||
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
|
||||
memcpy(hil_gps, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_GPS_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,377 @@
|
||||
// MESSAGE HIL_OPTICAL_FLOW PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114
|
||||
|
||||
typedef struct __mavlink_hil_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 in x-sensor direction
|
||||
int16_t flow_y; ///< Flow in pixels in y-sensor direction
|
||||
uint8_t sensor_id; ///< Sensor ID
|
||||
uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality
|
||||
} mavlink_hil_optical_flow_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 26
|
||||
#define MAVLINK_MSG_ID_114_LEN 26
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 119
|
||||
#define MAVLINK_MSG_ID_114_CRC 119
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \
|
||||
"HIL_OPTICAL_FLOW", \
|
||||
8, \
|
||||
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \
|
||||
{ "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_optical_flow_t, flow_comp_m_x) }, \
|
||||
{ "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, flow_comp_m_y) }, \
|
||||
{ "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, ground_distance) }, \
|
||||
{ "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_hil_optical_flow_t, flow_x) }, \
|
||||
{ "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_hil_optical_flow_t, flow_y) }, \
|
||||
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \
|
||||
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_hil_optical_flow_t, quality) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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 (UNIX)
|
||||
* @param sensor_id Sensor ID
|
||||
* @param flow_x Flow in pixels in x-sensor direction
|
||||
* @param flow_y Flow in pixels in y-sensor direction
|
||||
* @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_hil_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_HIL_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_HIL_OPTICAL_FLOW_LEN);
|
||||
#else
|
||||
mavlink_hil_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_HIL_OPTICAL_FLOW_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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 (UNIX)
|
||||
* @param sensor_id Sensor ID
|
||||
* @param flow_x Flow in pixels in x-sensor direction
|
||||
* @param flow_y Flow in pixels in y-sensor direction
|
||||
* @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_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,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_HIL_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_HIL_OPTICAL_FLOW_LEN);
|
||||
#else
|
||||
mavlink_hil_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_HIL_OPTICAL_FLOW_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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->flow_x, hil_optical_flow->flow_y, hil_optical_flow->flow_comp_m_x, hil_optical_flow->flow_comp_m_y, hil_optical_flow->quality, hil_optical_flow->ground_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->flow_x, hil_optical_flow->flow_y, hil_optical_flow->flow_comp_m_x, hil_optical_flow->flow_comp_m_y, hil_optical_flow->quality, hil_optical_flow->ground_distance);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a hil_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 in x-sensor direction
|
||||
* @param flow_y Flow in pixels in y-sensor direction
|
||||
* @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_hil_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_HIL_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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_hil_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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
|
||||
#endif
|
||||
#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, 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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_hil_optical_flow_t *packet = (mavlink_hil_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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE HIL_OPTICAL_FLOW UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field time_usec from hil_optical_flow message
|
||||
*
|
||||
* @return Timestamp (UNIX)
|
||||
*/
|
||||
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, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field flow_x from hil_optical_flow message
|
||||
*
|
||||
* @return Flow in pixels in x-sensor direction
|
||||
*/
|
||||
static inline int16_t mavlink_msg_hil_optical_flow_get_flow_x(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field flow_y from hil_optical_flow message
|
||||
*
|
||||
* @return Flow in pixels in y-sensor direction
|
||||
*/
|
||||
static inline int16_t mavlink_msg_hil_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 hil_optical_flow message
|
||||
*
|
||||
* @return Flow in meters in x-sensor direction, angular-speed compensated
|
||||
*/
|
||||
static inline float mavlink_msg_hil_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 hil_optical_flow message
|
||||
*
|
||||
* @return Flow in meters in y-sensor direction, angular-speed compensated
|
||||
*/
|
||||
static inline float mavlink_msg_hil_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field quality from hil_optical_flow message
|
||||
*
|
||||
* @return Optical flow quality / confidence. 0: bad, 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, 25);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field ground_distance from hil_optical_flow message
|
||||
*
|
||||
* @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
|
||||
*/
|
||||
static inline float mavlink_msg_hil_optical_flow_get_ground_distance(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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
|
||||
hil_optical_flow->time_usec = mavlink_msg_hil_optical_flow_get_time_usec(msg);
|
||||
hil_optical_flow->flow_comp_m_x = mavlink_msg_hil_optical_flow_get_flow_comp_m_x(msg);
|
||||
hil_optical_flow->flow_comp_m_y = mavlink_msg_hil_optical_flow_get_flow_comp_m_y(msg);
|
||||
hil_optical_flow->ground_distance = mavlink_msg_hil_optical_flow_get_ground_distance(msg);
|
||||
hil_optical_flow->flow_x = mavlink_msg_hil_optical_flow_get_flow_x(msg);
|
||||
hil_optical_flow->flow_y = mavlink_msg_hil_optical_flow_get_flow_y(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
|
||||
memcpy(hil_optical_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
|
||||
#endif
|
||||
}
|
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,353 @@
|
||||
// MESSAGE LOCAL_POSITION_NED PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32
|
||||
|
||||
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_32_LEN 28
|
||||
|
||||
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185
|
||||
#define MAVLINK_MSG_ID_32_CRC 185
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \
|
||||
"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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_local_position_ned_t packet;
|
||||
packet.time_boot_ms = time_boot_ms;
|
||||
packet.x = x;
|
||||
packet.y = y;
|
||||
packet.z = z;
|
||||
packet.vx = vx;
|
||||
packet.vy = vy;
|
||||
packet.vz = vz;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_local_position_ned_t *packet = (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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(local_position_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,417 @@
|
||||
// MESSAGE LOCAL_POSITION_NED_COV PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64
|
||||
|
||||
typedef struct __mavlink_local_position_ned_cov_t
|
||||
{
|
||||
uint64_t time_utc; ///< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
||||
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
|
||||
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_local_position_ned_cov_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 181
|
||||
#define MAVLINK_MSG_ID_64_LEN 181
|
||||
|
||||
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 82
|
||||
#define MAVLINK_MSG_ID_64_CRC 82
|
||||
|
||||
#define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 36
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \
|
||||
"LOCAL_POSITION_NED_COV", \
|
||||
10, \
|
||||
{ { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_utc) }, \
|
||||
{ "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_local_position_ned_cov_t, time_boot_ms) }, \
|
||||
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, x) }, \
|
||||
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, y) }, \
|
||||
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, z) }, \
|
||||
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vx) }, \
|
||||
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vy) }, \
|
||||
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, vz) }, \
|
||||
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \
|
||||
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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_boot_ms Timestamp (milliseconds since system boot)
|
||||
* @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
||||
* @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
|
||||
* @param vy Y Speed
|
||||
* @param vz Z Speed
|
||||
* @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_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, 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_utc);
|
||||
_mav_put_uint32_t(buf, 8, time_boot_ms);
|
||||
_mav_put_float(buf, 12, x);
|
||||
_mav_put_float(buf, 16, y);
|
||||
_mav_put_float(buf, 20, z);
|
||||
_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_LOCAL_POSITION_NED_COV_LEN);
|
||||
#else
|
||||
mavlink_local_position_ned_cov_t packet;
|
||||
packet.time_utc = time_utc;
|
||||
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.estimator_type = estimator_type;
|
||||
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
|
||||
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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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_boot_ms Timestamp (milliseconds since system boot)
|
||||
* @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
||||
* @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
|
||||
* @param vy Y Speed
|
||||
* @param vz Z Speed
|
||||
* @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_local_position_ned_cov_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 estimator_type,float x,float y,float z,float vx,float vy,float vz,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_utc);
|
||||
_mav_put_uint32_t(buf, 8, time_boot_ms);
|
||||
_mav_put_float(buf, 12, x);
|
||||
_mav_put_float(buf, 16, y);
|
||||
_mav_put_float(buf, 20, z);
|
||||
_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_LOCAL_POSITION_NED_COV_LEN);
|
||||
#else
|
||||
mavlink_local_position_ned_cov_t packet;
|
||||
packet.time_utc = time_utc;
|
||||
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.estimator_type = estimator_type;
|
||||
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
|
||||
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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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_boot_ms, local_position_ned_cov->time_utc, 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->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_boot_ms, local_position_ned_cov->time_utc, 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->covariance);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a local_position_ned_cov 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. Commonly filled by the precision time source of a GPS receiver.
|
||||
* @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
|
||||
* @param vy Y Speed
|
||||
* @param vz Z Speed
|
||||
* @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_local_position_ned_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, 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_utc);
|
||||
_mav_put_uint32_t(buf, 8, time_boot_ms);
|
||||
_mav_put_float(buf, 12, x);
|
||||
_mav_put_float(buf, 16, y);
|
||||
_mav_put_float(buf, 20, z);
|
||||
_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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_local_position_ned_cov_t packet;
|
||||
packet.time_utc = time_utc;
|
||||
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.estimator_type = estimator_type;
|
||||
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
||||
#endif
|
||||
#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, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, 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_utc);
|
||||
_mav_put_uint32_t(buf, 8, time_boot_ms);
|
||||
_mav_put_float(buf, 12, x);
|
||||
_mav_put_float(buf, 16, y);
|
||||
_mav_put_float(buf, 20, z);
|
||||
_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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_local_position_ned_cov_t *packet = (mavlink_local_position_ned_cov_t *)msgbuf;
|
||||
packet->time_utc = time_utc;
|
||||
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->estimator_type = estimator_type;
|
||||
mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE LOCAL_POSITION_NED_COV UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field time_boot_ms from local_position_ned_cov message
|
||||
*
|
||||
* @return Timestamp (milliseconds since system boot)
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_local_position_ned_cov_get_time_boot_ms(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint32_t(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field time_utc from local_position_ned_cov message
|
||||
*
|
||||
* @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
|
||||
*/
|
||||
static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_utc(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, 180);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field vx from local_position_ned_cov message
|
||||
*
|
||||
* @return X Speed
|
||||
*/
|
||||
static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field vy from local_position_ned_cov message
|
||||
*
|
||||
* @return Y Speed
|
||||
*/
|
||||
static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 28);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field vz from local_position_ned_cov message
|
||||
*
|
||||
* @return Z Speed
|
||||
*/
|
||||
static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 32);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field covariance from local_position_ned_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_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
|
||||
{
|
||||
return _MAV_RETURN_float_array(msg, covariance, 36, 36);
|
||||
}
|
||||
|
||||
/**
|
||||
* @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
|
||||
local_position_ned_cov->time_utc = mavlink_msg_local_position_ned_cov_get_time_utc(msg);
|
||||
local_position_ned_cov->time_boot_ms = mavlink_msg_local_position_ned_cov_get_time_boot_ms(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);
|
||||
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
|
||||
memcpy(local_position_ned_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,353 @@
|
||||
// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89
|
||||
|
||||
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_89_LEN 28
|
||||
|
||||
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231
|
||||
#define MAVLINK_MSG_ID_89_CRC 231
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \
|
||||
"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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_local_position_ned_system_global_offset_t packet;
|
||||
packet.time_boot_ms = time_boot_ms;
|
||||
packet.x = x;
|
||||
packet.y = y;
|
||||
packet.z = z;
|
||||
packet.roll = roll;
|
||||
packet.pitch = pitch;
|
||||
packet.yaw = yaw;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#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);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_local_position_ned_system_global_offset_t *packet = (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;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#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
|
||||
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
|
||||
memcpy(local_position_ned_system_global_offset, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
|
||||
#endif
|
||||
}
|
||||
@@ -0,0 +1,273 @@
|
||||
// MESSAGE LOG_DATA PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_LOG_DATA 120
|
||||
|
||||
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_120_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
|
||||
|
||||
#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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN);
|
||||
#endif
|
||||
#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);
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN);
|
||||
#endif
|
||||
#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
|
||||
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
|
||||
memcpy(log_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_DATA_LEN);
|
||||
#endif
|
||||
}
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user