Commit edc1f169 authored by lm's avatar lm

Ported to final MAVLink v1.0 draft

parent 685e048b
......@@ -394,7 +394,7 @@ void MAVLinkProtocol::sendHeartbeat()
{
if (m_heartbeatsEnabled) {
mavlink_message_t beat;
mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL, 0, MAV_STATE_ACTIVE);
mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL_ARMED, 0, MAV_STATE_ACTIVE);
sendMessage(beat);
}
if (m_authEnabled) {
......
......@@ -382,14 +382,14 @@ void MAVLinkSimulationLink::mainloop()
// Send back new setpoint
mavlink_message_t ret;
mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, spX, spY, spZ, spYaw);
mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, MAV_FRAME_LOCAL_NED, spX, spY, spZ, spYaw);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// Send back new position
mavlink_msg_local_position_pack(systemId, componentId, &ret, 0, x, y, -fabs(z), xSpeed, ySpeed, zSpeed);
mavlink_msg_local_position_ned_pack(systemId, componentId, &ret, 0, x, y, -fabs(z), xSpeed, ySpeed, zSpeed);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
......@@ -403,7 +403,7 @@ void MAVLinkSimulationLink::mainloop()
// streampointer += bufferlength;
// GLOBAL POSITION
mavlink_msg_global_position_int_pack(systemId, componentId, &ret, 0, (473780.28137103+(x))*1E3, (85489.9892510421+(y))*1E3, (z+550.0)*1000.0, xSpeed, ySpeed, zSpeed, yaw);
mavlink_msg_global_position_int_pack(systemId, componentId, &ret, 0, (473780.28137103+(x))*1E3, (85489.9892510421+(y))*1E3, (z+550.0)*1000.0, (z+550.0)*1000.0-1, xSpeed, ySpeed, zSpeed, yaw);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
......@@ -432,6 +432,7 @@ void MAVLinkSimulationLink::mainloop()
if (rcCounter == 2) {
mavlink_rc_channels_raw_t chan;
chan.time_boot_ms = 0;
chan.port = 0;
chan.chan1_raw = 1000 + ((int)(fabs(x) * 1000) % 2000);
chan.chan2_raw = 1000 + ((int)(fabs(y) * 1000) % 2000);
chan.chan3_raw = 1000 + ((int)(fabs(z) * 1000) % 2000);
......@@ -694,7 +695,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
// Send back new setpoint
mavlink_message_t ret;
mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, spX, spY, spZ, spYaw);
mavlink_msg_local_position_setpoint_pack(systemId, componentId, &ret, MAV_FRAME_LOCAL_NED, spX, spY, spZ, spYaw);
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
......
......@@ -40,7 +40,7 @@ MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int sy
nextSPYaw(0.0),
sys_mode(MAV_MODE_PREFLIGHT),
sys_state(MAV_STATE_STANDBY),
nav_mode(MAV_AUTOPILOT_CUSTOM_MODE_PREFLIGHT),
nav_mode(0),
flying(false),
mavlink_version(version)
{
......@@ -61,14 +61,14 @@ void MAVLinkSimulationMAV::mainloop()
if (flying) {
sys_state = MAV_STATE_ACTIVE;
sys_mode = MAV_MODE_AUTO;
nav_mode = MAV_AUTOPILOT_CUSTOM_MODE_AUTO_MISSION;
sys_mode = MAV_MODE_AUTO_ARMED;
nav_mode = 0;
}
// 1 Hz execution
if (timer1Hz <= 0) {
mavlink_message_t msg;
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_MODE_GUIDED, MAV_AUTOPILOT_CUSTOM_MODE_AUTO_MISSION, MAV_STATE_ACTIVE);
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE);
link->sendMAVLinkMessage(&msg);
planner.handleMessage(msg);
......@@ -322,7 +322,7 @@ void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
mavlink_set_local_position_setpoint_t sp;
mavlink_msg_set_local_position_setpoint_decode(&msg, &sp);
if (sp.target_system == this->systemid) {
nav_mode = MAV_AUTOPILOT_CUSTOM_MODE_AUTO_MISSION;
nav_mode = 0;
previousSPX = nextSPX;
previousSPY = nextSPY;
previousSPZ = nextSPZ;
......
......@@ -37,11 +37,11 @@ protected:
uint64_t timestamp_lastoutside_orbit;///< timestamp when the MAV was last outside the orbit or had the wrong yaw value
uint64_t timestamp_firstinside_orbit;///< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value
std::vector<mavlink_waypoint_t*> waypoints1; ///< vector1 that holds the waypoints
std::vector<mavlink_waypoint_t*> waypoints2; ///< vector2 that holds the waypoints
std::vector<mavlink_mission_item_t*> waypoints1; ///< vector1 that holds the waypoints
std::vector<mavlink_mission_item_t*> waypoints2; ///< vector2 that holds the waypoints
std::vector<mavlink_waypoint_t*>* waypoints; ///< pointer to the currently active waypoint vector
std::vector<mavlink_waypoint_t*>* waypoints_receive_buffer; ///< pointer to the receive buffer waypoint vector
std::vector<mavlink_mission_item_t*>* waypoints; ///< pointer to the currently active waypoint vector
std::vector<mavlink_mission_item_t*>* waypoints_receive_buffer; ///< pointer to the receive buffer waypoint vector
PX_WAYPOINTPLANNER_STATES current_state;
uint16_t protocol_current_wp_id;
uint16_t protocol_current_count;
......
This diff is collapsed.
......@@ -323,10 +323,10 @@ public:
case MAV_AUTOPILOT_OPENPILOT:
return "OPENPILOT";
break;
case MAV_AUTOPILOT_GENERIC_MISSION_WAYPOINTS_ONLY:
return "GENERIC_MISSION_WAYPOINTS_ONLY";
case MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY:
return "GENERIC_WAYPOINTS_ONLY";
break;
case MAV_AUTOPILOT_GENERIC_MISSION_NAVIGATION_ONLY:
case MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY:
return "GENERIC_MISSION_NAVIGATION_ONLY";
break;
case MAV_AUTOPILOT_GENERIC_MISSION_FULL:
......
This diff is collapsed.
......@@ -68,11 +68,11 @@ public:
/** @name Received message handlers */
/*@{*/
void handleWaypointCount(quint8 systemId, quint8 compId, quint16 count); ///< Handles received waypoint count messages
void handleWaypoint(quint8 systemId, quint8 compId, mavlink_waypoint_t *wp); ///< Handles received waypoint messages
void handleWaypointAck(quint8 systemId, quint8 compId, mavlink_waypoint_ack_t *wpa); ///< Handles received waypoint ack messages
void handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_waypoint_request_t *wpr); ///< Handles received waypoint request messages
void handleWaypointReached(quint8 systemId, quint8 compId, mavlink_waypoint_reached_t *wpr); ///< Handles received waypoint reached messages
void handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_waypoint_current_t *wpc); ///< Handles received set current waypoint messages
void handleWaypoint(quint8 systemId, quint8 compId, mavlink_mission_item_t *wp); ///< Handles received waypoint messages
void handleWaypointAck(quint8 systemId, quint8 compId, mavlink_mission_ack_t *wpa); ///< Handles received waypoint ack messages
void handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr); ///< Handles received waypoint request messages
void handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr); ///< Handles received waypoint reached messages
void handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc); ///< Handles received set current waypoint messages
/*@}*/
/** @name Remote operations */
......@@ -159,7 +159,7 @@ private:
quint8 current_partner_compid; ///< The current protocol communication target component
QVector<Waypoint *> waypoints; ///< local waypoint list (main storage)
QVector<mavlink_waypoint_t *> waypoint_buffer; ///< buffer for waypoints during communication
QVector<mavlink_mission_item_t *> waypoint_buffer; ///< buffer for waypoints during communication
QTimer protocol_timer; ///< Timer to catch timeouts
};
......
......@@ -269,8 +269,8 @@ void DebugConsole::receiveTextMessage(int id, int component, int severity, QStri
case MAV_COMP_ID_MAPPER:
comp = tr("MAPPER");
break;
case MAV_COMP_ID_WAYPOINTPLANNER:
comp = tr("WP-PLANNER");
case MAV_COMP_ID_MISSIONPLANNER:
comp = tr("MISSION");
break;
case MAV_COMP_ID_SYSTEM_CONTROL:
comp = tr("SYS-CONTROL");
......
......@@ -67,7 +67,7 @@ protected:
QUdpSocket* rxSocket;
UAS* activeUas;
mavlink_local_position_t tmpLocalPositionData;
mavlink_local_position_ned_t tmpLocalPositionData;
mavlink_attitude_t tmpAttitudeData;
mavlink_raw_imu_t tmpRawImuData;
#ifdef MAVLINK_ENABLED_SLUGS
......
......@@ -55,8 +55,11 @@ void UASControlParameters::changedMode(int mode)
case (uint8_t)MAV_MODE_PREFLIGHT:
modeTemp = "LOCKED MODE";
break;
case (uint8_t)MAV_MODE_MANUAL:
modeTemp = "MANUAL MODE";
case (uint8_t)MAV_MODE_MANUAL_ARMED:
modeTemp = "A/MANUAL MODE";
break;
case (uint8_t)MAV_MODE_MANUAL_DISARMED:
modeTemp = "D/MANUAL MODE";
break;
#ifdef MAVLINK_ENABLED_SLUGS
case (uint8_t)MAV_MODE_AUTO:
......@@ -72,20 +75,9 @@ void UASControlParameters::changedMode(int mode)
case (uint8_t)MAV_MODE_TEST2:
modeTemp = "SEL PT MODE";
break;
#else
case (uint8_t)MAV_MODE_AUTO:
modeTemp = "AUTO MODE";
break;
case (uint8_t)MAV_MODE_GUIDED:
modeTemp = "GUIDED MODE";
break;
case (uint8_t)MAV_MODE_TEST:
modeTemp = "TEST1 MODE";
break;
#endif
default:
modeTemp = "UNINIT MODE";
modeTemp = "UNKNOWN MODE";
break;
}
......
......@@ -51,11 +51,11 @@ UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent),
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
ui.modeComboBox->clear();
ui.modeComboBox->insertItem(MAV_MODE_PREFLIGHT, UAS::getShortModeTextFor(MAV_MODE_PREFLIGHT));
ui.modeComboBox->insertItem(MAV_MODE_STABILIZE, UAS::getShortModeTextFor(MAV_MODE_STABILIZE));
ui.modeComboBox->insertItem(MAV_MODE_MANUAL, UAS::getShortModeTextFor(MAV_MODE_MANUAL));
ui.modeComboBox->insertItem(MAV_MODE_GUIDED, UAS::getShortModeTextFor(MAV_MODE_GUIDED));
ui.modeComboBox->insertItem(MAV_MODE_AUTO, UAS::getShortModeTextFor(MAV_MODE_AUTO));
ui.modeComboBox->insertItem(MAV_MODE_TEST, UAS::getShortModeTextFor(MAV_MODE_TEST));
ui.modeComboBox->insertItem(MAV_MODE_STABILIZE_ARMED, UAS::getShortModeTextFor(MAV_MODE_STABILIZE_ARMED));
ui.modeComboBox->insertItem(MAV_MODE_MANUAL_ARMED, UAS::getShortModeTextFor(MAV_MODE_MANUAL_ARMED));
ui.modeComboBox->insertItem(MAV_MODE_GUIDED_DISARMED, UAS::getShortModeTextFor(MAV_MODE_GUIDED_ARMED));
ui.modeComboBox->insertItem(MAV_MODE_AUTO_ARMED, UAS::getShortModeTextFor(MAV_MODE_AUTO_ARMED));
ui.modeComboBox->insertItem(MAV_MODE_TEST_ARMED, UAS::getShortModeTextFor(MAV_MODE_TEST_ARMED));
connect(ui.modeComboBox, SIGNAL(activated(int)), this, SLOT(setMode(int)));
connect(ui.setModeButton, SIGNAL(clicked()), this, SLOT(transmitMode()));
......
......@@ -26,18 +26,18 @@ typedef struct __mavlink_sensor_offsets_t
#define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \
"SENSOR_OFFSETS", \
12, \
{ { "mag_declination", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \
{ "raw_press", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_sensor_offsets_t, raw_press) }, \
{ "raw_temp", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \
{ "gyro_cal_x", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \
{ "gyro_cal_y", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \
{ "gyro_cal_z", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \
{ "accel_cal_x", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \
{ "accel_cal_y", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \
{ "accel_cal_z", MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \
{ "mag_ofs_x", MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \
{ { "mag_declination", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \
{ "raw_press", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_sensor_offsets_t, raw_press) }, \
{ "raw_temp", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \
{ "gyro_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \
{ "gyro_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \
{ "gyro_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \
{ "accel_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \
{ "accel_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \
{ "accel_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \
{ "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \
} \
}
......
......@@ -19,11 +19,11 @@ typedef struct __mavlink_set_mag_offsets_t
#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \
"SET_MAG_OFFSETS", \
5, \
{ { "mag_ofs_x", MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \
{ "target_system", MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \
{ "target_component", MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \
{ { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \
} \
}
......
......@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Aug 31 10:19:04 2011"
#define MAVLINK_BUILD_DATE "Fri Sep 2 16:29:29 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h"
......
......@@ -5,8 +5,6 @@ extern "C" {
#ifndef _CHECKSUM_H_
#define _CHECKSUM_H_
#include "inttypes.h"
/**
*
......
This diff is collapsed.
// MESSAGE ATTITUDE PACKING
#define MAVLINK_MSG_ID_ATTITUDE 31
#define MAVLINK_MSG_ID_ATTITUDE 30
typedef struct __mavlink_attitude_t
{
......@@ -14,20 +14,20 @@ typedef struct __mavlink_attitude_t
} mavlink_attitude_t;
#define MAVLINK_MSG_ID_ATTITUDE_LEN 28
#define MAVLINK_MSG_ID_31_LEN 28
#define MAVLINK_MSG_ID_30_LEN 28
#define MAVLINK_MESSAGE_INFO_ATTITUDE { \
"ATTITUDE", \
7, \
{ { "time_boot_ms", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
{ "roll", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
{ "pitch", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
{ "yaw", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
{ "rollspeed", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
{ "pitchspeed", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
{ "yawspeed", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
{ { "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) }, \
} \
}
......
......@@ -15,7 +15,7 @@ typedef struct __mavlink_auth_key_t
#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \
"AUTH_KEY", \
1, \
{ { "key", MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
{ { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
} \
}
......
......@@ -18,10 +18,10 @@ typedef struct __mavlink_change_operator_control_t
#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \
"CHANGE_OPERATOR_CONTROL", \
4, \
{ { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \
{ "control_request", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \
{ "version", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \
{ "passkey", MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \
{ { "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) }, \
} \
}
......
......@@ -17,9 +17,9 @@ typedef struct __mavlink_change_operator_control_ack_t
#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \
"CHANGE_OPERATOR_CONTROL_ACK", \
3, \
{ { "gcs_system_id", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \
{ "control_request", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \
{ "ack", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \
{ { "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) }, \
} \
}
......
......@@ -16,8 +16,8 @@ typedef struct __mavlink_command_ack_t
#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
"COMMAND_ACK", \
2, \
{ { "command", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
{ "result", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_ack_t, result) }, \
{ { "command", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
{ "result", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_ack_t, result) }, \
} \
}
......
......@@ -25,17 +25,17 @@ typedef struct __mavlink_command_long_t
#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \
"COMMAND_LONG", \
11, \
{ { "param1", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
{ "param2", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \
{ "param3", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \
{ "param4", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \
{ "param5", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \
{ "param6", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \
{ "param7", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \
{ "target_system", MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_command_long_t, target_system) }, \
{ "target_component", MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_command_long_t, target_component) }, \
{ "command", MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, command) }, \
{ "confirmation", MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, confirmation) }, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \
{ "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \
{ "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \
{ "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_command_long_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_command_long_t, target_component) }, \
{ "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, command) }, \
{ "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, confirmation) }, \
} \
}
......
......@@ -22,14 +22,14 @@ typedef struct __mavlink_command_short_t
#define MAVLINK_MESSAGE_INFO_COMMAND_SHORT { \
"COMMAND_SHORT", \
8, \
{ { "param1", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_short_t, param1) }, \
{ "param2", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_short_t, param2) }, \
{ "param3", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_short_t, param3) }, \
{ "param4", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_short_t, param4) }, \
{ "target_system", MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_command_short_t, target_system) }, \
{ "target_component", MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_command_short_t, target_component) }, \
{ "command", MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_command_short_t, command) }, \
{ "confirmation", MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_command_short_t, confirmation) }, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_short_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_short_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_short_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_short_t, param4) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_command_short_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_command_short_t, target_component) }, \
{ "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_command_short_t, command) }, \
{ "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_command_short_t, confirmation) }, \
} \
}
......
......@@ -17,9 +17,9 @@ typedef struct __mavlink_data_stream_t
#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \
"DATA_STREAM", \
3, \
{ { "message_rate", MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \
{ "stream_id", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \
{ "on_off", MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \
{ { "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) }, \
} \
}
......
......@@ -17,9 +17,9 @@ typedef struct __mavlink_debug_t
#define MAVLINK_MESSAGE_INFO_DEBUG { \
"DEBUG", \
3, \
{ { "time_boot_ms", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \
{ "value", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \
{ "ind", MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \
{ { "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) }, \
} \
}
......
......@@ -19,11 +19,11 @@ typedef struct __mavlink_debug_vect_t
#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
"DEBUG_VECT", \
5, \
{ { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
{ "x", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
{ "y", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
{ "z", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
{ "name", MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
} \
}
......
......@@ -17,9 +17,9 @@ typedef struct __mavlink_extended_message_t
#define MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE { \
"EXTENDED_MESSAGE", \
3, \
{ { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_message_t, target_system) }, \
{ "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_message_t, target_component) }, \
{ "protocol_flags", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_extended_message_t, protocol_flags) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_message_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_message_t, target_component) }, \
{ "protocol_flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_extended_message_t, protocol_flags) }, \
} \
}
......
// MESSAGE GLOBAL_POSITION PACKING
#define MAVLINK_MSG_ID_GLOBAL_POSITION 33
typedef struct __mavlink_global_position_t
{
uint64_t usec; ///< Timestamp (microseconds since unix epoch)
float lat; ///< Latitude, in degrees
float lon; ///< Longitude, in degrees
float alt; ///< Absolute altitude, in meters
float vx; ///< X Speed (in Latitude direction, positive: going north)
float vy; ///< Y Speed (in Longitude direction, positive: going east)
float vz; ///< Z Speed (in Altitude direction, positive: going up)
} mavlink_global_position_t;
#define MAVLINK_MSG_ID_GLOBAL_POSITION_LEN 32
#define MAVLINK_MSG_ID_33_LEN 32
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION { \
"GLOBAL_POSITION", \
7, \
{ { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_t, usec) }, \
{ "lat", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_position_t, lat) }, \
{ "lon", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_position_t, lon) }, \
{ "alt", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_position_t, alt) }, \
{ "vx", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_t, vx) }, \
{ "vy", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_t, vy) }, \
{ "vz", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_t, vz) }, \
} \
}
/**
* @brief Pack a global_position message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, lat);
_mav_put_float(buf, 12, lon);
_mav_put_float(buf, 16, alt);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
memcpy(_MAV_PAYLOAD(msg), buf, 32);
#else
mavlink_global_position_t packet;
packet.usec = usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
memcpy(_MAV_PAYLOAD(msg), &packet, 32);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
return mavlink_finalize_message(msg, system_id, component_id, 32, 147);
}
/**
* @brief Pack a global_position message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float lat,float lon,float alt,float vx,float vy,float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, lat);
_mav_put_float(buf, 12, lon);
_mav_put_float(buf, 16, alt);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
memcpy(_MAV_PAYLOAD(msg), buf, 32);
#else
mavlink_global_position_t packet;
packet.usec = usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
memcpy(_MAV_PAYLOAD(msg), &packet, 32);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 147);
}
/**
* @brief Encode a global_position struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param global_position C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position)
{
return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz);
}
/**
* @brief Send a global_position message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, lat);
_mav_put_float(buf, 12, lon);
_mav_put_float(buf, 16, alt);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION, buf, 32, 147);
#else
mavlink_global_position_t packet;
packet.usec = usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION, (const char *)&packet, 32, 147);
#endif
}
#endif
// MESSAGE GLOBAL_POSITION UNPACKING
/**
* @brief Get field usec from global_position message
*
* @return Timestamp (microseconds since unix epoch)
*/
static inline uint64_t mavlink_msg_global_position_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field lat from global_position message
*
* @return Latitude, in degrees
*/
static inline float mavlink_msg_global_position_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field lon from global_position message
*
* @return Longitude, in degrees
*/
static inline float mavlink_msg_global_position_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field alt from global_position message
*
* @return Absolute altitude, in meters
*/
static inline float mavlink_msg_global_position_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field vx from global_position message
*
* @return X Speed (in Latitude direction, positive: going north)
*/
static inline float mavlink_msg_global_position_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field vy from global_position message
*
* @return Y Speed (in Longitude direction, positive: going east)
*/
static inline float mavlink_msg_global_position_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field vz from global_position message
*
* @return Z Speed (in Altitude direction, positive: going up)
*/
static inline float mavlink_msg_global_position_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Decode a global_position message into a struct
*
* @param msg The message to decode
* @param global_position C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_position_decode(const mavlink_message_t* msg, mavlink_global_position_t* global_position)
{
#if MAVLINK_NEED_BYTE_SWAP
global_position->usec = mavlink_msg_global_position_get_usec(msg);
global_position->lat = mavlink_msg_global_position_get_lat(msg);
global_position->lon = mavlink_msg_global_position_get_lon(msg);
global_position->alt = mavlink_msg_global_position_get_alt(msg);
global_position->vx = mavlink_msg_global_position_get_vx(msg);
global_position->vy = mavlink_msg_global_position_get_vy(msg);
global_position->vz = mavlink_msg_global_position_get_vz(msg);
#else
memcpy(global_position, _MAV_PAYLOAD(msg), 32);
#endif
}
......@@ -8,20 +8,22 @@ typedef struct __mavlink_global_position_setpoint_int_t
int32_t longitude; ///< WGS84 Longitude position in degrees * 1E7
int32_t altitude; ///< WGS84 Altitude in meters * 1000 (positive for up)
int16_t yaw; ///< Desired yaw angle in degrees * 100
uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
} mavlink_global_position_setpoint_int_t;
#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 14
#define MAVLINK_MSG_ID_52_LEN 14
#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 15
#define MAVLINK_MSG_ID_52_LEN 15
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT { \
"GLOBAL_POSITION_SETPOINT_INT", \
4, \
{ { "latitude", MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_setpoint_int_t, latitude) }, \
{ "longitude", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_setpoint_int_t, longitude) }, \
{ "altitude", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_setpoint_int_t, altitude) }, \
{ "yaw", MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_setpoint_int_t, yaw) }, \
5, \
{ { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_setpoint_int_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_setpoint_int_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_setpoint_int_t, altitude) }, \
{ "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_setpoint_int_t, yaw) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_global_position_setpoint_int_t, coordinate_frame) }, \
} \
}
......@@ -32,6 +34,7 @@ typedef struct __mavlink_global_position_setpoint_int_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
* @param latitude WGS84 Latitude position in degrees * 1E7
* @param longitude WGS84 Longitude position in degrees * 1E7
* @param altitude WGS84 Altitude in meters * 1000 (positive for up)
......@@ -39,28 +42,30 @@ typedef struct __mavlink_global_position_setpoint_int_t
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
char buf[15];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_int16_t(buf, 12, yaw);
_mav_put_uint8_t(buf, 14, coordinate_frame);
memcpy(_MAV_PAYLOAD(msg), buf, 14);
memcpy(_MAV_PAYLOAD(msg), buf, 15);
#else
mavlink_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
memcpy(_MAV_PAYLOAD(msg), &packet, 14);
memcpy(_MAV_PAYLOAD(msg), &packet, 15);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT;
return mavlink_finalize_message(msg, system_id, component_id, 14, 142);
return mavlink_finalize_message(msg, system_id, component_id, 15, 141);
}
/**
......@@ -69,6 +74,7 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t sys
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
* @param latitude WGS84 Latitude position in degrees * 1E7
* @param longitude WGS84 Longitude position in degrees * 1E7
* @param altitude WGS84 Altitude in meters * 1000 (positive for up)
......@@ -77,28 +83,30 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t sys
*/
static inline uint16_t mavlink_msg_global_position_setpoint_int_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,int16_t yaw)
uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
char buf[15];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_int16_t(buf, 12, yaw);
_mav_put_uint8_t(buf, 14, coordinate_frame);
memcpy(_MAV_PAYLOAD(msg), buf, 14);
memcpy(_MAV_PAYLOAD(msg), buf, 15);
#else
mavlink_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
memcpy(_MAV_PAYLOAD(msg), &packet, 14);
memcpy(_MAV_PAYLOAD(msg), &packet, 15);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 142);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 141);
}
/**
......@@ -111,13 +119,14 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_pack_chan(uint8_
*/
static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_setpoint_int_t* global_position_setpoint_int)
{
return mavlink_msg_global_position_setpoint_int_pack(system_id, component_id, msg, global_position_setpoint_int->latitude, global_position_setpoint_int->longitude, global_position_setpoint_int->altitude, global_position_setpoint_int->yaw);
return mavlink_msg_global_position_setpoint_int_pack(system_id, component_id, msg, global_position_setpoint_int->coordinate_frame, global_position_setpoint_int->latitude, global_position_setpoint_int->longitude, global_position_setpoint_int->altitude, global_position_setpoint_int->yaw);
}
/**
* @brief Send a global_position_setpoint_int message
* @param chan MAVLink channel to send the message
*
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
* @param latitude WGS84 Latitude position in degrees * 1E7
* @param longitude WGS84 Longitude position in degrees * 1E7
* @param altitude WGS84 Altitude in meters * 1000 (positive for up)
......@@ -125,24 +134,26 @@ static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t s
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
char buf[15];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_int16_t(buf, 12, yaw);
_mav_put_uint8_t(buf, 14, coordinate_frame);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, 14, 142);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, 15, 141);
#else
mavlink_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 14, 142);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 15, 141);
#endif
}
......@@ -151,6 +162,16 @@ static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel
// MESSAGE GLOBAL_POSITION_SETPOINT_INT UNPACKING
/**
* @brief Get field coordinate_frame from global_position_setpoint_int message
*
* @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
*/
static inline uint8_t mavlink_msg_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 14);
}
/**
* @brief Get field latitude from global_position_setpoint_int message
*
......@@ -204,7 +225,8 @@ static inline void mavlink_msg_global_position_setpoint_int_decode(const mavlink
global_position_setpoint_int->longitude = mavlink_msg_global_position_setpoint_int_get_longitude(msg);
global_position_setpoint_int->altitude = mavlink_msg_global_position_setpoint_int_get_altitude(msg);
global_position_setpoint_int->yaw = mavlink_msg_global_position_setpoint_int_get_yaw(msg);
global_position_setpoint_int->coordinate_frame = mavlink_msg_global_position_setpoint_int_get_coordinate_frame(msg);
#else
memcpy(global_position_setpoint_int, _MAV_PAYLOAD(msg), 14);
memcpy(global_position_setpoint_int, _MAV_PAYLOAD(msg), 15);
#endif
}
......@@ -17,9 +17,9 @@ typedef struct __mavlink_gps_global_origin_t
#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \
"GPS_GLOBAL_ORIGIN", \
3, \
{ { "latitude", MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \
{ "longitude", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \
{ "altitude", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \
{ { "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) }, \
} \
}
......
// MESSAGE GPS_RAW_INT PACKING
#define MAVLINK_MSG_ID_GPS_RAW_INT 25
#define MAVLINK_MSG_ID_GPS_RAW_INT 24
typedef struct __mavlink_gps_raw_int_t
{
......@@ -17,23 +17,23 @@ typedef struct __mavlink_gps_raw_int_t
} mavlink_gps_raw_int_t;
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
#define MAVLINK_MSG_ID_25_LEN 30
#define MAVLINK_MSG_ID_24_LEN 30
#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
"GPS_RAW_INT", \
10, \
{ { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
{ "lat", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
{ "lon", MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
{ "alt", MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
{ "eph", MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
{ "epv", MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
{ "vel", MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
{ "cog", MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
{ "fix_type", MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "satellites_visible", MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
{ { "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) }, \
} \
}
......
// MESSAGE GPS_SET_GLOBAL_ORIGIN PACKING
#define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN 48
typedef struct __mavlink_gps_set_global_origin_t
{
int32_t latitude; ///< global position * 1E7
int32_t longitude; ///< global position * 1E7
int32_t altitude; ///< global position * 1000
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_gps_set_global_origin_t;
#define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN_LEN 14
#define MAVLINK_MSG_ID_48_LEN 14
#define MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN { \
"GPS_SET_GLOBAL_ORIGIN", \
5, \
{ { "latitude", MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_set_global_origin_t, latitude) }, \
{ "longitude", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_set_global_origin_t, longitude) }, \
{ "altitude", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_set_global_origin_t, altitude) }, \
{ "target_system", MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gps_set_global_origin_t, target_system) }, \
{ "target_component", MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_gps_set_global_origin_t, target_component) }, \
} \
}
/**
* @brief Pack a gps_set_global_origin message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
memcpy(_MAV_PAYLOAD(msg), buf, 14);
#else
mavlink_gps_set_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD(msg), &packet, 14);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
return mavlink_finalize_message(msg, system_id, component_id, 14, 170);
}
/**
* @brief Pack a gps_set_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 was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_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,int32_t latitude,int32_t longitude,int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
memcpy(_MAV_PAYLOAD(msg), buf, 14);
#else
mavlink_gps_set_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD(msg), &packet, 14);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 170);
}
/**
* @brief Encode a gps_set_global_origin struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_set_global_origin C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_set_global_origin_t* gps_set_global_origin)
{
return mavlink_msg_gps_set_global_origin_pack(system_id, component_id, msg, gps_set_global_origin->target_system, gps_set_global_origin->target_component, gps_set_global_origin->latitude, gps_set_global_origin->longitude, gps_set_global_origin->altitude);
}
/**
* @brief Send a gps_set_global_origin message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN, buf, 14, 170);
#else
mavlink_gps_set_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN, (const char *)&packet, 14, 170);
#endif
}
#endif
// MESSAGE GPS_SET_GLOBAL_ORIGIN UNPACKING
/**
* @brief Get field target_system from gps_set_global_origin message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Get field target_component from gps_set_global_origin message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
/**
* @brief Get field latitude from gps_set_global_origin message
*
* @return global position * 1E7
*/
static inline int32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field longitude from gps_set_global_origin message
*
* @return global position * 1E7
*/
static inline int32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field altitude from gps_set_global_origin message
*
* @return global position * 1000
*/
static inline int32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Decode a gps_set_global_origin message into a struct
*
* @param msg The message to decode
* @param gps_set_global_origin C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_set_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_set_global_origin_t* gps_set_global_origin)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_set_global_origin->latitude = mavlink_msg_gps_set_global_origin_get_latitude(msg);
gps_set_global_origin->longitude = mavlink_msg_gps_set_global_origin_get_longitude(msg);
gps_set_global_origin->altitude = mavlink_msg_gps_set_global_origin_get_altitude(msg);
gps_set_global_origin->target_system = mavlink_msg_gps_set_global_origin_get_target_system(msg);
gps_set_global_origin->target_component = mavlink_msg_gps_set_global_origin_get_target_component(msg);
#else
memcpy(gps_set_global_origin, _MAV_PAYLOAD(msg), 14);
#endif
}
// MESSAGE GPS_STATUS PACKING
#define MAVLINK_MSG_ID_GPS_STATUS 26
#define MAVLINK_MSG_ID_GPS_STATUS 25
typedef struct __mavlink_gps_status_t
{
......@@ -13,7 +13,7 @@ typedef struct __mavlink_gps_status_t
} mavlink_gps_status_t;
#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
#define MAVLINK_MSG_ID_26_LEN 101
#define MAVLINK_MSG_ID_25_LEN 101
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
......@@ -24,12 +24,12 @@ typedef struct __mavlink_gps_status_t
#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \
"GPS_STATUS", \
6, \
{ { "satellites_visible", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \
{ "satellite_prn", MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \
{ "satellite_used", MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \
{ "satellite_elevation", MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \
{ "satellite_azimuth", MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \
{ "satellite_snr", MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \
{ { "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) }, \
} \
}
......
......@@ -4,7 +4,7 @@
typedef struct __mavlink_heartbeat_t
{
uint16_t custom_mode; ///< Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
uint32_t custom_mode; ///< Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
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_CLASS ENUM
uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
......@@ -12,20 +12,20 @@ typedef struct __mavlink_heartbeat_t
uint8_t mavlink_version; ///< MAVLink version
} mavlink_heartbeat_t;
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 7
#define MAVLINK_MSG_ID_0_LEN 7
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9
#define MAVLINK_MSG_ID_0_LEN 9
#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
"HEARTBEAT", \
6, \
{ { "custom_mode", MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
{ "type", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_heartbeat_t, type) }, \
{ "autopilot", MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_heartbeat_t, autopilot) }, \
{ "base_mode", MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, base_mode) }, \
{ "system_status", MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, system_status) }, \
{ "mavlink_version", MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
{ { "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) }, \
} \
}
......@@ -44,18 +44,18 @@ typedef struct __mavlink_heartbeat_t
* @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, uint16_t custom_mode, uint8_t system_status)
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[7];
_mav_put_uint16_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 2, type);
_mav_put_uint8_t(buf, 3, autopilot);
_mav_put_uint8_t(buf, 4, base_mode);
_mav_put_uint8_t(buf, 5, system_status);
_mav_put_uint8_t(buf, 6, 3);
memcpy(_MAV_PAYLOAD(msg), buf, 7);
char buf[9];
_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(msg), buf, 9);
#else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
......@@ -65,11 +65,11 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com
packet.system_status = system_status;
packet.mavlink_version = 3;
memcpy(_MAV_PAYLOAD(msg), &packet, 7);
memcpy(_MAV_PAYLOAD(msg), &packet, 9);
#endif
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
return mavlink_finalize_message(msg, system_id, component_id, 7, 88);
return mavlink_finalize_message(msg, system_id, component_id, 9, 50);
}
/**
......@@ -87,18 +87,18 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com
*/
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,uint16_t custom_mode,uint8_t system_status)
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[7];
_mav_put_uint16_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 2, type);
_mav_put_uint8_t(buf, 3, autopilot);
_mav_put_uint8_t(buf, 4, base_mode);
_mav_put_uint8_t(buf, 5, system_status);
_mav_put_uint8_t(buf, 6, 3);
memcpy(_MAV_PAYLOAD(msg), buf, 7);
char buf[9];
_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(msg), buf, 9);
#else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
......@@ -108,11 +108,11 @@ static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_
packet.system_status = system_status;
packet.mavlink_version = 3;
memcpy(_MAV_PAYLOAD(msg), &packet, 7);
memcpy(_MAV_PAYLOAD(msg), &packet, 9);
#endif
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 7, 88);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 50);
}
/**
......@@ -140,18 +140,18 @@ static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t c
*/
#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, uint16_t custom_mode, uint8_t system_status)
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[7];
_mav_put_uint16_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 2, type);
_mav_put_uint8_t(buf, 3, autopilot);
_mav_put_uint8_t(buf, 4, base_mode);
_mav_put_uint8_t(buf, 5, system_status);
_mav_put_uint8_t(buf, 6, 3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 7, 88);
char buf[9];
_mav_put_uint32_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 4, type);
_mav_put_uint8_t(buf, 5, autopilot);
_mav_put_uint8_t(buf, 6, base_mode);
_mav_put_uint8_t(buf, 7, system_status);
_mav_put_uint8_t(buf, 8, 3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 9, 50);
#else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
......@@ -161,7 +161,7 @@ static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t ty
packet.system_status = system_status;
packet.mavlink_version = 3;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 7, 88);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 9, 50);
#endif
}
......@@ -177,7 +177,7 @@ static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t ty
*/
static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
......@@ -187,7 +187,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* ms
*/
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
......@@ -197,7 +197,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_
*/
static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
......@@ -205,9 +205,9 @@ static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_
*
* @return Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
*/
static inline uint16_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
......@@ -217,7 +217,7 @@ static inline uint16_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_messa
*/
static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
......@@ -227,7 +227,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_mess
*/
static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
......@@ -246,6 +246,6 @@ static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, ma
heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg);
heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
#else
memcpy(heartbeat, _MAV_PAYLOAD(msg), 7);
memcpy(heartbeat, _MAV_PAYLOAD(msg), 9);
#endif
}
......@@ -25,17 +25,17 @@ typedef struct __mavlink_hil_controls_t
#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \
"HIL_CONTROLS", \
11, \
{ { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \
{ "roll_ailerons", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \
{ "pitch_elevator", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \
{ "yaw_rudder", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \
{ "throttle", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \
{ "aux1", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \
{ "aux2", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \
{ "aux3", MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \
{ "aux4", MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \
{ "mode", MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \
{ "nav_mode", MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \
{ { "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) }, \
} \
}
......
......@@ -28,20 +28,20 @@ typedef struct __mavlink_hil_rc_inputs_raw_t
#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \
"HIL_RC_INPUTS_RAW", \
14, \
{ { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \
{ "chan1_raw", MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \
{ "chan2_raw", MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \
{ "chan3_raw", MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \
{ "chan4_raw", MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \
{ "chan5_raw", MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \
{ "chan6_raw", MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \
{ "chan7_raw", MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \
{ "chan8_raw", MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \
{ "chan9_raw", MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \
{ "chan10_raw", MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \
{ "chan11_raw", MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \
{ "chan12_raw", MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \
{ "rssi", MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \
{ "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \
{ "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \
{ "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \
{ "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \
{ "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \
{ "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \
{ "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \
{ "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \
{ "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \
{ "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \
{ "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \
{ "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \
} \
}
......
......@@ -30,22 +30,22 @@ typedef struct __mavlink_hil_state_t
#define MAVLINK_MESSAGE_INFO_HIL_STATE { \
"HIL_STATE", \
16, \
{ { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \
{ "roll", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \
{ "pitch", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \
{ "yaw", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \
{ "rollspeed", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \
{ "pitchspeed", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \
{ "yawspeed", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \
{ "lat", MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \
{ "lon", MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \
{ "alt", MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \
{ "vx", MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \
{ "vy", MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \
{ "vz", MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \
{ "xacc", MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \
{ "yacc", MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \
{ "zacc", MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \
{ "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \
} \
}
......
......@@ -8,20 +8,22 @@ typedef struct __mavlink_local_position_setpoint_t
float y; ///< y position
float z; ///< z position
float yaw; ///< Desired yaw angle
uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
} mavlink_local_position_setpoint_t;
#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 16
#define MAVLINK_MSG_ID_51_LEN 16
#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 17
#define MAVLINK_MSG_ID_51_LEN 17
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT { \
"LOCAL_POSITION_SETPOINT", \
4, \
{ { "x", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_local_position_setpoint_t, x) }, \
{ "y", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_setpoint_t, y) }, \
{ "z", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_setpoint_t, z) }, \
{ "yaw", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_setpoint_t, yaw) }, \
5, \
{ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_local_position_setpoint_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_setpoint_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_setpoint_t, z) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_setpoint_t, yaw) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_local_position_setpoint_t, coordinate_frame) }, \
} \
}
......@@ -32,6 +34,7 @@ typedef struct __mavlink_local_position_setpoint_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
* @param x x position
* @param y y position
* @param z z position
......@@ -39,28 +42,30 @@ typedef struct __mavlink_local_position_setpoint_t
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float x, float y, float z, float yaw)
uint8_t coordinate_frame, float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
char buf[17];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
_mav_put_uint8_t(buf, 16, coordinate_frame);
memcpy(_MAV_PAYLOAD(msg), buf, 16);
memcpy(_MAV_PAYLOAD(msg), buf, 17);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
memcpy(_MAV_PAYLOAD(msg), &packet, 16);
memcpy(_MAV_PAYLOAD(msg), &packet, 17);
#endif
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 16, 50);
return mavlink_finalize_message(msg, system_id, component_id, 17, 223);
}
/**
......@@ -69,6 +74,7 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_i
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
* @param x x position
* @param y y position
* @param z z position
......@@ -77,28 +83,30 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_i
*/
static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float x,float y,float z,float yaw)
uint8_t coordinate_frame,float x,float y,float z,float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
char buf[17];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
_mav_put_uint8_t(buf, 16, coordinate_frame);
memcpy(_MAV_PAYLOAD(msg), buf, 16);
memcpy(_MAV_PAYLOAD(msg), buf, 17);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
memcpy(_MAV_PAYLOAD(msg), &packet, 16);
memcpy(_MAV_PAYLOAD(msg), &packet, 17);
#endif
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 50);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 17, 223);
}
/**
......@@ -111,13 +119,14 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t sys
*/
static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint)
{
return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw);
return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->coordinate_frame, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw);
}
/**
* @brief Send a local_position_setpoint message
* @param chan MAVLink channel to send the message
*
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
* @param x x position
* @param y y position
* @param z z position
......@@ -125,24 +134,26 @@ static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, uint8_t coordinate_frame, float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
char buf[17];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
_mav_put_uint8_t(buf, 16, coordinate_frame);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, 16, 50);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, 17, 223);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, 16, 50);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, 17, 223);
#endif
}
......@@ -151,6 +162,16 @@ static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t ch
// MESSAGE LOCAL_POSITION_SETPOINT UNPACKING
/**
* @brief Get field coordinate_frame from local_position_setpoint message
*
* @return Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
*/
static inline uint8_t mavlink_msg_local_position_setpoint_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
/**
* @brief Get field x from local_position_setpoint message
*
......@@ -204,7 +225,8 @@ static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_mess
local_position_setpoint->y = mavlink_msg_local_position_setpoint_get_y(msg);
local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg);
local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg);
local_position_setpoint->coordinate_frame = mavlink_msg_local_position_setpoint_get_coordinate_frame(msg);
#else
memcpy(local_position_setpoint, _MAV_PAYLOAD(msg), 16);
memcpy(local_position_setpoint, _MAV_PAYLOAD(msg), 17);
#endif
}
......@@ -23,15 +23,15 @@ typedef struct __mavlink_manual_control_t
#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \
"MANUAL_CONTROL", \
9, \
{ { "roll", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_manual_control_t, roll) }, \
{ "pitch", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_control_t, pitch) }, \
{ "yaw", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_control_t, yaw) }, \
{ "thrust", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_control_t, thrust) }, \
{ "target", MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_manual_control_t, target) }, \
{ "roll_manual", MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_manual_control_t, roll_manual) }, \
{ "pitch_manual", MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_manual_control_t, pitch_manual) }, \
{ "yaw_manual", MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_manual_control_t, yaw_manual) }, \
{ "thrust_manual", MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_control_t, thrust_manual) }, \
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_manual_control_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_control_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_control_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_control_t, thrust) }, \
{ "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_manual_control_t, target) }, \
{ "roll_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_manual_control_t, roll_manual) }, \
{ "pitch_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_manual_control_t, pitch_manual) }, \
{ "yaw_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_manual_control_t, yaw_manual) }, \
{ "thrust_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_control_t, thrust_manual) }, \
} \
}
......
......@@ -18,10 +18,10 @@ typedef struct __mavlink_memory_vect_t
#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \
"MEMORY_VECT", \
4, \
{ { "address", MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \
{ "ver", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \
{ "type", MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \
{ "value", MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \
{ { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \
{ "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \
{ "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \
} \
}
......
// MESSAGE WAYPOINT_CLEAR_ALL PACKING
// MESSAGE MISSION_CLEAR_ALL PACKING
#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL 45
#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45
typedef struct __mavlink_waypoint_clear_all_t
typedef struct __mavlink_mission_clear_all_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_waypoint_clear_all_t;
} mavlink_mission_clear_all_t;
#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL_LEN 2
#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2
#define MAVLINK_MSG_ID_45_LEN 2
#define MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL { \
"WAYPOINT_CLEAR_ALL", \
#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \
"MISSION_CLEAR_ALL", \
2, \
{ { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_clear_all_t, target_system) }, \
{ "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_clear_all_t, target_component) }, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \
} \
}
/**
* @brief Pack a waypoint_clear_all message
* @brief Pack a mission_clear_all message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
......@@ -32,7 +32,7 @@ typedef struct __mavlink_waypoint_clear_all_t
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
......@@ -42,19 +42,19 @@ static inline uint16_t mavlink_msg_waypoint_clear_all_pack(uint8_t system_id, ui
memcpy(_MAV_PAYLOAD(msg), buf, 2);
#else
mavlink_waypoint_clear_all_t packet;
mavlink_mission_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD(msg), &packet, 2);
#endif
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL;
return mavlink_finalize_message(msg, system_id, component_id, 2, 229);
msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL;
return mavlink_finalize_message(msg, system_id, component_id, 2, 232);
}
/**
* @brief Pack a waypoint_clear_all message on a channel
* @brief Pack a mission_clear_all message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
......@@ -63,7 +63,7 @@ static inline uint16_t mavlink_msg_waypoint_clear_all_pack(uint8_t system_id, ui
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component)
{
......@@ -74,32 +74,32 @@ static inline uint16_t mavlink_msg_waypoint_clear_all_pack_chan(uint8_t system_i
memcpy(_MAV_PAYLOAD(msg), buf, 2);
#else
mavlink_waypoint_clear_all_t packet;
mavlink_mission_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD(msg), &packet, 2);
#endif
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 229);
msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 232);
}
/**
* @brief Encode a waypoint_clear_all struct into a message
* @brief Encode a mission_clear_all struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint_clear_all C-struct to read the message contents from
* @param mission_clear_all C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_clear_all_t* waypoint_clear_all)
static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all)
{
return mavlink_msg_waypoint_clear_all_pack(system_id, component_id, msg, waypoint_clear_all->target_system, waypoint_clear_all->target_component);
return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component);
}
/**
* @brief Send a waypoint_clear_all message
* @brief Send a mission_clear_all message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
......@@ -107,60 +107,60 @@ static inline uint16_t mavlink_msg_waypoint_clear_all_encode(uint8_t system_id,
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL, buf, 2, 229);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, 2, 232);
#else
mavlink_waypoint_clear_all_t packet;
mavlink_mission_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL, (const char *)&packet, 2, 229);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, 2, 232);
#endif
}
#endif
// MESSAGE WAYPOINT_CLEAR_ALL UNPACKING
// MESSAGE MISSION_CLEAR_ALL UNPACKING
/**
* @brief Get field target_system from waypoint_clear_all message
* @brief Get field target_system from mission_clear_all message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_system(const mavlink_message_t* msg)
static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from waypoint_clear_all message
* @brief Get field target_component from mission_clear_all message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_component(const mavlink_message_t* msg)
static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Decode a waypoint_clear_all message into a struct
* @brief Decode a mission_clear_all message into a struct
*
* @param msg The message to decode
* @param waypoint_clear_all C-struct to decode the message contents into
* @param mission_clear_all C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_clear_all_decode(const mavlink_message_t* msg, mavlink_waypoint_clear_all_t* waypoint_clear_all)
static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t* msg, mavlink_mission_clear_all_t* mission_clear_all)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint_clear_all->target_system = mavlink_msg_waypoint_clear_all_get_target_system(msg);
waypoint_clear_all->target_component = mavlink_msg_waypoint_clear_all_get_target_component(msg);
mission_clear_all->target_system = mavlink_msg_mission_clear_all_get_target_system(msg);
mission_clear_all->target_component = mavlink_msg_mission_clear_all_get_target_component(msg);
#else
memcpy(waypoint_clear_all, _MAV_PAYLOAD(msg), 2);
memcpy(mission_clear_all, _MAV_PAYLOAD(msg), 2);
#endif
}
// MESSAGE WAYPOINT_COUNT PACKING
// MESSAGE MISSION_COUNT PACKING
#define MAVLINK_MSG_ID_WAYPOINT_COUNT 44
#define MAVLINK_MSG_ID_MISSION_COUNT 44
typedef struct __mavlink_waypoint_count_t
typedef struct __mavlink_mission_count_t
{
uint16_t count; ///< Number of Waypoints in the Sequence
uint16_t count; ///< Number of MISSIONs in the Sequence
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_waypoint_count_t;
} mavlink_mission_count_t;
#define MAVLINK_MSG_ID_WAYPOINT_COUNT_LEN 4
#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4
#define MAVLINK_MSG_ID_44_LEN 4
#define MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT { \
"WAYPOINT_COUNT", \
#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \
"MISSION_COUNT", \
3, \
{ { "count", MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_count_t, count) }, \
{ "target_system", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_waypoint_count_t, target_system) }, \
{ "target_component", MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_waypoint_count_t, target_component) }, \
{ { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \
} \
}
/**
* @brief Pack a waypoint_count message
* @brief Pack a mission_count message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param count Number of Waypoints in the Sequence
* @param count Number of MISSIONs in the Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
......@@ -46,7 +46,7 @@ static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_
memcpy(_MAV_PAYLOAD(msg), buf, 4);
#else
mavlink_waypoint_count_t packet;
mavlink_mission_count_t packet;
packet.count = count;
packet.target_system = target_system;
packet.target_component = target_component;
......@@ -54,22 +54,22 @@ static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_
memcpy(_MAV_PAYLOAD(msg), &packet, 4);
#endif
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT;
return mavlink_finalize_message(msg, system_id, component_id, 4, 8);
msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT;
return mavlink_finalize_message(msg, system_id, component_id, 4, 221);
}
/**
* @brief Pack a waypoint_count message on a channel
* @brief Pack a mission_count message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param count Number of Waypoints in the Sequence
* @param count Number of MISSIONs in the Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint16_t count)
{
......@@ -81,7 +81,7 @@ static inline uint16_t mavlink_msg_waypoint_count_pack_chan(uint8_t system_id, u
memcpy(_MAV_PAYLOAD(msg), buf, 4);
#else
mavlink_waypoint_count_t packet;
mavlink_mission_count_t packet;
packet.count = count;
packet.target_system = target_system;
packet.target_component = target_component;
......@@ -89,34 +89,34 @@ static inline uint16_t mavlink_msg_waypoint_count_pack_chan(uint8_t system_id, u
memcpy(_MAV_PAYLOAD(msg), &packet, 4);
#endif
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 8);
msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 221);
}
/**
* @brief Encode a waypoint_count struct into a message
* @brief Encode a mission_count struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint_count C-struct to read the message contents from
* @param mission_count C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_count_t* waypoint_count)
static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count)
{
return mavlink_msg_waypoint_count_pack(system_id, component_id, msg, waypoint_count->target_system, waypoint_count->target_component, waypoint_count->count);
return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count);
}
/**
* @brief Send a waypoint_count message
* @brief Send a mission_count message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param count Number of Waypoints in the Sequence
* @param count Number of MISSIONs in the Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count)
static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
......@@ -124,65 +124,65 @@ static inline void mavlink_msg_waypoint_count_send(mavlink_channel_t chan, uint8
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_COUNT, buf, 4, 8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, 4, 221);
#else
mavlink_waypoint_count_t packet;
mavlink_mission_count_t packet;
packet.count = count;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_COUNT, (const char *)&packet, 4, 8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, 4, 221);
#endif
}
#endif
// MESSAGE WAYPOINT_COUNT UNPACKING
// MESSAGE MISSION_COUNT UNPACKING
/**
* @brief Get field target_system from waypoint_count message
* @brief Get field target_system from mission_count message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_waypoint_count_get_target_system(const mavlink_message_t* msg)
static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field target_component from waypoint_count message
* @brief Get field target_component from mission_count message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_waypoint_count_get_target_component(const mavlink_message_t* msg)
static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field count from waypoint_count message
* @brief Get field count from mission_count message
*
* @return Number of Waypoints in the Sequence
* @return Number of MISSIONs in the Sequence
*/
static inline uint16_t mavlink_msg_waypoint_count_get_count(const mavlink_message_t* msg)
static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Decode a waypoint_count message into a struct
* @brief Decode a mission_count message into a struct
*
* @param msg The message to decode
* @param waypoint_count C-struct to decode the message contents into
* @param mission_count C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_count_decode(const mavlink_message_t* msg, mavlink_waypoint_count_t* waypoint_count)
static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint_count->count = mavlink_msg_waypoint_count_get_count(msg);
waypoint_count->target_system = mavlink_msg_waypoint_count_get_target_system(msg);
waypoint_count->target_component = mavlink_msg_waypoint_count_get_target_component(msg);
mission_count->count = mavlink_msg_mission_count_get_count(msg);
mission_count->target_system = mavlink_msg_mission_count_get_target_system(msg);
mission_count->target_component = mavlink_msg_mission_count_get_target_component(msg);
#else
memcpy(waypoint_count, _MAV_PAYLOAD(msg), 4);
memcpy(mission_count, _MAV_PAYLOAD(msg), 4);
#endif
}
// MESSAGE WAYPOINT_CURRENT PACKING
// MESSAGE MISSION_CURRENT PACKING
#define MAVLINK_MSG_ID_WAYPOINT_CURRENT 42
#define MAVLINK_MSG_ID_MISSION_CURRENT 42
typedef struct __mavlink_waypoint_current_t
typedef struct __mavlink_mission_current_t
{
uint16_t seq; ///< Sequence
} mavlink_waypoint_current_t;
} mavlink_mission_current_t;
#define MAVLINK_MSG_ID_WAYPOINT_CURRENT_LEN 2
#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2
#define MAVLINK_MSG_ID_42_LEN 2
#define MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT { \
"WAYPOINT_CURRENT", \
#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \
"MISSION_CURRENT", \
1, \
{ { "seq", MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_current_t, seq) }, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \
} \
}
/**
* @brief Pack a waypoint_current message
* @brief Pack a mission_current message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
......@@ -29,7 +29,7 @@ typedef struct __mavlink_waypoint_current_t
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
......@@ -38,18 +38,18 @@ static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint
memcpy(_MAV_PAYLOAD(msg), buf, 2);
#else
mavlink_waypoint_current_t packet;
mavlink_mission_current_t packet;
packet.seq = seq;
memcpy(_MAV_PAYLOAD(msg), &packet, 2);
#endif
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT;
return mavlink_finalize_message(msg, system_id, component_id, 2, 101);
msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT;
return mavlink_finalize_message(msg, system_id, component_id, 2, 28);
}
/**
* @brief Pack a waypoint_current message on a channel
* @brief Pack a mission_current message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
......@@ -57,7 +57,7 @@ static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t seq)
{
......@@ -67,78 +67,78 @@ static inline uint16_t mavlink_msg_waypoint_current_pack_chan(uint8_t system_id,
memcpy(_MAV_PAYLOAD(msg), buf, 2);
#else
mavlink_waypoint_current_t packet;
mavlink_mission_current_t packet;
packet.seq = seq;
memcpy(_MAV_PAYLOAD(msg), &packet, 2);
#endif
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 101);
msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 28);
}
/**
* @brief Encode a waypoint_current struct into a message
* @brief Encode a mission_current struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint_current C-struct to read the message contents from
* @param mission_current C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_current_t* waypoint_current)
static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current)
{
return mavlink_msg_waypoint_current_pack(system_id, component_id, msg, waypoint_current->seq);
return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq);
}
/**
* @brief Send a waypoint_current message
* @brief Send a mission_current message
* @param chan MAVLink channel to send the message
*
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_current_send(mavlink_channel_t chan, uint16_t seq)
static inline void mavlink_msg_mission_current_send(mavlink_channel_t chan, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CURRENT, buf, 2, 101);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, 2, 28);
#else
mavlink_waypoint_current_t packet;
mavlink_mission_current_t packet;
packet.seq = seq;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CURRENT, (const char *)&packet, 2, 101);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, 2, 28);
#endif
}
#endif
// MESSAGE WAYPOINT_CURRENT UNPACKING
// MESSAGE MISSION_CURRENT UNPACKING
/**
* @brief Get field seq from waypoint_current message
* @brief Get field seq from mission_current message
*
* @return Sequence
*/
static inline uint16_t mavlink_msg_waypoint_current_get_seq(const mavlink_message_t* msg)
static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Decode a waypoint_current message into a struct
* @brief Decode a mission_current message into a struct
*
* @param msg The message to decode
* @param waypoint_current C-struct to decode the message contents into
* @param mission_current C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_current_decode(const mavlink_message_t* msg, mavlink_waypoint_current_t* waypoint_current)
static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint_current->seq = mavlink_msg_waypoint_current_get_seq(msg);
mission_current->seq = mavlink_msg_mission_current_get_seq(msg);
#else
memcpy(waypoint_current, _MAV_PAYLOAD(msg), 2);
memcpy(mission_current, _MAV_PAYLOAD(msg), 2);
#endif
}
......@@ -17,9 +17,9 @@ typedef struct __mavlink_named_value_float_t
#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \
"NAMED_VALUE_FLOAT", \
3, \
{ { "time_boot_ms", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \
{ "value", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \
{ "name", MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \
} \
}
......
......@@ -17,9 +17,9 @@ typedef struct __mavlink_named_value_int_t
#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \
"NAMED_VALUE_INT", \
3, \
{ { "time_boot_ms", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \
{ "value", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \
{ "name", MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \
} \
}
......
......@@ -10,8 +10,8 @@ typedef struct __mavlink_nav_controller_output_t
float aspd_error; ///< Current airspeed error in meters/second
float xtrack_error; ///< Current crosstrack error on x-y plane in meters
int16_t nav_bearing; ///< Current desired heading in degrees
int16_t target_bearing; ///< Bearing to current waypoint/target in degrees
uint16_t wp_dist; ///< Distance to active waypoint in meters
int16_t target_bearing; ///< Bearing to current MISSION/target in degrees
uint16_t wp_dist; ///< Distance to active MISSION in meters
} mavlink_nav_controller_output_t;
#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26
......@@ -22,14 +22,14 @@ typedef struct __mavlink_nav_controller_output_t
#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \
"NAV_CONTROLLER_OUTPUT", \
8, \
{ { "nav_roll", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \
{ "nav_pitch", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \
{ "alt_error", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \
{ "aspd_error", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \
{ "xtrack_error", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \
{ "nav_bearing", MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \
{ "target_bearing", MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \
{ "wp_dist", MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \
{ { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \
{ "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \
{ "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \
{ "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \
{ "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \
{ "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \
{ "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \
{ "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \
} \
}
......@@ -43,8 +43,8 @@ typedef struct __mavlink_nav_controller_output_t
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current waypoint/target in degrees
* @param wp_dist Distance to active waypoint in meters
* @param target_bearing Bearing to current MISSION/target in degrees
* @param wp_dist Distance to active MISSION in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
......@@ -92,8 +92,8 @@ static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id,
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current waypoint/target in degrees
* @param wp_dist Distance to active waypoint in meters
* @param target_bearing Bearing to current MISSION/target in degrees
* @param wp_dist Distance to active MISSION in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
......@@ -153,8 +153,8 @@ static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_i
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current waypoint/target in degrees
* @param wp_dist Distance to active waypoint in meters
* @param target_bearing Bearing to current MISSION/target in degrees
* @param wp_dist Distance to active MISSION in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
......@@ -228,7 +228,7 @@ static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const ma
/**
* @brief Get field target_bearing from nav_controller_output message
*
* @return Bearing to current waypoint/target in degrees
* @return Bearing to current MISSION/target in degrees
*/
static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg)
{
......@@ -238,7 +238,7 @@ static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const
/**
* @brief Get field wp_dist from nav_controller_output message
*
* @return Distance to active waypoint in meters
* @return Distance to active MISSION in meters
*/
static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg)
{
......
......@@ -20,12 +20,12 @@ typedef struct __mavlink_optical_flow_t
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \
"OPTICAL_FLOW", \
6, \
{ { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
{ "ground_distance", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, ground_distance) }, \
{ "flow_x", MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_optical_flow_t, flow_x) }, \
{ "flow_y", MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_optical_flow_t, flow_y) }, \
{ "sensor_id", MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "quality", MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_optical_flow_t, quality) }, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
{ "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, ground_distance) }, \
{ "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_optical_flow_t, flow_x) }, \
{ "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_optical_flow_t, flow_y) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_optical_flow_t, quality) }, \
} \
}
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment