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
*