Commit b303e674 authored by lm's avatar lm

Added MAVLink inspector

parent a02927bf
......@@ -31,9 +31,6 @@
#include "QGCMAVLinkUASFactory.h"
#include "QGC.h"
// Instantiate MAVLink data
#include "mavlink_data.h"
/**
* The default constructor will create a new MAVLink object sending heartbeats at
* the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
......@@ -377,7 +374,8 @@ void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message
// Create buffer
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
// Rewriting header to ensure correct link ID is set
if (link->getId() != 0) mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getId(), message.len);
static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
if (link->getId() != 0) mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
// Write message into buffer, prepending start sign
int len = mavlink_msg_to_send_buffer(buffer, &message);
// If link is connected
......
......@@ -91,6 +91,7 @@ Size PlateCarreeProjection::GetTileMatrixMaxXY(const int &zoom)
Size PlateCarreeProjection::GetTileMatrixMinXY(const int &zoom)
{
Q_UNUSED(zoom);
return Size(0, 0);
}
}
......@@ -90,6 +90,7 @@ Size PlateCarreeProjectionPergo::GetTileMatrixMaxXY(const int &zoom)
Size PlateCarreeProjectionPergo::GetTileMatrixMinXY(const int &zoom)
{
Q_UNUSED(zoom);
return Size(0, 0);
}
}
......@@ -32,7 +32,15 @@
namespace mapcontrol
{
MapGraphicItem::MapGraphicItem(internals::Core *core, Configuration *configuration):core(core),config(configuration),MapRenderTransform(1), maxZoom(17),minZoom(2),zoomReal(0),isSelected(false),rotation(0),zoomDigi(0)
MapGraphicItem::MapGraphicItem(internals::Core *core, Configuration *configuration):core(core),
config(configuration),
MapRenderTransform(1),
maxZoom(17),
minZoom(2),
zoomReal(0),
rotation(0),
zoomDigi(0),
isSelected(false)
{
dragons.load(QString::fromUtf8(":/markers/images/dragons1.jpg"));
showTileGridLines=false;
......
......@@ -52,7 +52,15 @@ namespace mapcontrol
RefreshToolTip();
RefreshPos();
}
WayPointItem::WayPointItem(const internals::PointLatLng &coord,double const& altitude, const QString &description, MapGraphicItem *map):coord(coord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),heading(0),map(map)
WayPointItem::WayPointItem(const internals::PointLatLng &coord,double const& altitude, const QString &description, MapGraphicItem *map) :
coord(coord),
reached(false),
description(description),
shownumber(true),
isDragging(false),
altitude(altitude),
map(map),
heading(0)
{
text=0;
numberI=0;
......
......@@ -1431,7 +1431,8 @@ void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
// Write message into buffer, prepending start sign
int len = mavlink_msg_to_send_buffer(buffer, &message);
mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len);
static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
// If link is connected
if (link->isConnected())
{
......
This diff is collapsed.
......@@ -27,9 +27,13 @@ public slots:
protected:
QMap<int, quint64> lastFieldUpdate; ///< Used to switch between highlight and non-highlighting color
QMap<int, mavlink_message_t> receivedMessages; ///< Available / known messages
mavlink_message_t receivedMessages[256]; ///< Available / known messages
QMap<int, QTreeWidgetItem*> treeWidgetItems; ///< Available tree widget items
QTimer updateTimer; ///< Only update at 1 Hz to not overload the GUI
mavlink_message_info_t messageInfo[256];
// Update one message field
void updateField(int msgid, int fieldid, QTreeWidgetItem* item);
private:
Ui::QGCMAVLinkInspector *ui;
......
......@@ -13,11 +13,11 @@
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<layout class="QGridLayout" name="gridLayout" columnstretch="2,8">
<property name="margin">
<number>6</number>
</property>
<item row="0" column="0">
<item row="1" column="0" colspan="2">
<widget class="QTreeWidget" name="treeWidget">
<column>
<property name="text">
......@@ -26,6 +26,16 @@
</column>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="label">
<property name="text">
<string>System Filter</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QComboBox" name="systemComboBox"/>
</item>
</layout>
</widget>
<resources/>
......
......@@ -295,10 +295,9 @@ void QGCParamWidget::addComponent(int uas, int component, QString componentName)
components->value(component)->setData(1, Qt::DisplayRole, QString::number(component));
} else {
// Add new
QStringList list;
list.append(componentName);
list.append(QString::number(component));
QStringList list(QString("%1 (#%2)").arg(componentName).arg(component));
QTreeWidgetItem* comp = new QTreeWidgetItem(list);
comp->setFirstColumnSpanned(true);
components->insert(component, comp);
// Create grouping and update maps
paramGroups.insert(component, new QMap<QString, QTreeWidgetItem*>());
......
/** @file
* @brief MAVLink comm protocol.
* @brief MAVLink comm protocol generated from ardupilotmega.xml
* @see http://qgroundcontrol.org/mavlink/
* Generated on Saturday, August 20 2011, 11:19 UTC
*/
#ifndef ARDUPILOTMEGA_H
#define ARDUPILOTMEGA_H
......@@ -10,44 +9,46 @@
extern "C" {
#endif
// MESSAGE LENGTHS AND CRCS
#include "../mavlink_protocol.h"
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {8, 23, 12, 8, 14, 28, 3, 32, 0, 0, 0, 2, 2, 2, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 0, 30, 26, 101, 26, 16, 32, 32, 38, 32, 0, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 14, 27, 25, 18, 18, 20, 20, 0, 0, 0, 26, 16, 36, 0, 6, 4, 0, 21, 18, 0, 0, 20, 20, 20, 32, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 14, 14, 51, 5}
#endif
#define MAVLINK_ENABLED_ARDUPILOTMEGA
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {153, 114, 143, 191, 105, 217, 104, 119, 0, 0, 0, 186, 194, 8, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 0, 185, 222, 23, 179, 136, 66, 126, 198, 147, 0, 252, 162, 215, 229, 205, 51, 80, 101, 213, 8, 229, 21, 214, 170, 14, 73, 50, 142, 15, 3, 100, 24, 141, 148, 0, 0, 0, 183, 126, 130, 0, 148, 21, 0, 52, 124, 0, 0, 241, 20, 160, 168, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 250, 156, 0, 0, 0, 0, 0, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 15, 248, 63, 83, 127}
#endif
#ifndef MAVLINK_MESSAGE_INFO
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {}, {}, {}, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_FLIGHT_MODE, MAVLINK_MESSAGE_INFO_SET_SAFETY_MODE, {}, {}, {}, {}, {}, {}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, {}, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {}, {}, {}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {}, {}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_SHORT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {}, {}, {}, {}, {}, {}, {}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, {}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG}
#endif
#include "../protocol.h"
#define MAVLINK_ENABLED_ARDUPILOTMEGA
#include "../common/common.h"
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#define MAVLINK_VERSION 2
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#define MAVLINK_VERSION 2
#endif
// ENUM DEFINITIONS
// MESSAGE DEFINITIONS
// MESSAGE DEFINITIONS
#include "./mavlink_msg_sensor_offsets.h"
#include "./mavlink_msg_set_mag_offsets.h"
// MESSAGE CRC KEYS
#undef MAVLINK_MESSAGE_KEYS
#define MAVLINK_MESSAGE_KEYS { 179, 218, 22, 76, 226, 126, 117, 186, 0, 144, 0, 249, 172, 16, 0, 0, 0, 0, 0, 0, 33, 34, 191, 55, 0, 166, 28, 99, 28, 21, 243, 240, 91, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 20, 247, 234, 161, 116, 56, 245, 0, 0, 0, 62, 75, 185, 18, 42, 80, 0, 127, 200, 0, 0, 212, 251, 20, 38, 22, 0, 0, 0, 0, 0, 0, 0, 127, 0, 0, 0, 0, 18, 103, 59, 0, 0, 0, 0, 0, 0, 0, 74, 8, 238, 165, 0, 0, 0, 0, 0, 0, 0, 218, 218, 235, 0, 0, 0, 0, 0, 0, 225, 114, 0, 0, 0, 0, 0, 0, 0, 0, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 171, 122, 0, 0, 0, 0, 0, 0, 0, 226, 65, 4, 169, 10, 0, 0, 0, 0, 0, 52, 163, 16, 0, 0, 0, 0, 0, 0, 0, 200, 135, 217, 254, 0, 0, 255, 185, 0, 14, 136, 53, 0, 212, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 255, 73, 239, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 138, 43, 141, 211, 144 }
// MESSAGE LENGTHS
#undef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS { 8, 23, 12, 8, 14, 28, 3, 32, 0, 0, 0, 2, 2, 2, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 0, 30, 26, 101, 26, 16, 32, 32, 38, 32, 0, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 14, 27, 25, 18, 18, 20, 20, 0, 0, 0, 26, 16, 36, 0, 6, 4, 0, 21, 18, 0, 0, 20, 20, 20, 32, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 14, 14, 51 }
#ifdef __cplusplus
}
#endif
#endif
#endif // __cplusplus
#endif // ARDUPILOTMEGA_H
/** @file
* @brief MAVLink comm protocol testsuite generated from ardupilotmega.xml
* @see http://qgroundcontrol.org/mavlink/
* Generated on Wed Aug 24 17:14:16 2011
*/
#ifndef ARDUPILOTMEGA_TESTSUITE_H
#define ARDUPILOTMEGA_TESTSUITE_H
#ifdef __cplusplus
extern "C" {
#endif
static void mavtest_generate_outputs(mavlink_channel_t chan)
{
mavlink_msg_sensor_offsets_send(chan , 19107 , 19211 , 19315 , 17.0 , 963497672 , 963497880 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 , 241.0 );
mavlink_msg_set_mag_offsets_send(chan , 151 , 218 , 17235 , 17339 , 17443 );
}
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // ARDUPILOTMEGA_TESTSUITE_H
/** @file
* @brief MAVLink comm protocol.
* @brief MAVLink comm protocol built from ardupilotmega.xml
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Saturday, August 20 2011, 11:19 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
#pragma pack(push,1)
#include "mavlink_options.h"
#include "ardupilotmega.h"
#ifdef MAVLINK_DATA
#include "mavlink_data.h"
#ifndef MAVLINK_STX
#define MAVLINK_STX 254
#endif
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
#endif
#pragma pack(pop)
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 1
#endif
#include "version.h"
#include "ardupilotmega.h"
#endif // MAVLINK_H
/** @file
* @brief MAVLink comm protocol testsuite generated from ardupilotmega.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef ARDUPILOTMEGA_TESTSUITE_H
#define ARDUPILOTMEGA_TESTSUITE_H
#ifdef __cplusplus
extern "C" {
#endif
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
static void mavlink_test_common(uint8_t, uint8_t);
static void mavlink_test_ardupilotmega(uint8_t, uint8_t);
static void mavlink_test_all(uint8_t system_id, uint8_t component_id)
{
mavlink_test_common(system_id, component_id);
mavlink_test_ardupilotmega(system_id, component_id);
}
#endif
#include "../common/testsuite.h"
static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_sensor_offsets_t packet2, packet1 = {
17.0,
963497672,
963497880,
101.0,
129.0,
157.0,
185.0,
213.0,
241.0,
19107,
19211,
19315,
};
if (sizeof(packet2) != 42) {
packet2 = packet1; // cope with alignment within the packet
}
mavlink_msg_sensor_offsets_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_sensor_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
mavlink_msg_sensor_offsets_pack(system_id, component_id, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_sensor_offsets_pack_chan_send(MAVLINK_COMM_1, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_sensor_offsets_send(MAVLINK_COMM_2 , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
}
static void mavlink_test_set_mag_offsets(uint8_t system_id, uint8_t component_id)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_mag_offsets_t packet2, packet1 = {
17235,
17339,
17443,
151,
218,
};
if (sizeof(packet2) != 8) {
packet2 = packet1; // cope with alignment within the packet
}
mavlink_msg_set_mag_offsets_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
mavlink_msg_set_mag_offsets_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_mag_offsets_pack_chan_send(MAVLINK_COMM_1, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_set_mag_offsets_send(MAVLINK_COMM_2 , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
}
static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id)
{
mavlink_test_sensor_offsets(system_id, component_id);
mavlink_test_set_mag_offsets(system_id, component_id);
}
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // ARDUPILOTMEGA_TESTSUITE_H
/** @file
* @brief MAVLink comm protocol built from ardupilotmega.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Aug 27 10:06:30 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h"
#endif // MAVLINK_VERSION_H
......@@ -31,10 +31,9 @@ static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
/*Accumulate one byte of data into the CRC*/
uint8_t tmp;
tmp=data ^ (uint8_t)(*crcAccum &0xff);
tmp^= (tmp<<4);
tmp = data ^ (uint8_t)(*crcAccum &0xff);
tmp ^= (tmp<<4);
*crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
// *crcAccum += data; // super simple to test
}
/**
......@@ -57,76 +56,12 @@ static inline void crc_init(uint16_t* crcAccum)
**/
static inline uint16_t crc_calculate(uint8_t* pBuffer, int length)
{
// For a "message" of length bytes contained in the unsigned char array
// pointed to by pBuffer, calculate the CRC
// crcCalculate(unsigned char* pBuffer, int length, unsigned short* checkConst) < not needed
uint16_t crcTmp;
//uint16_t tmp;
uint8_t* pTmp;
int i;
pTmp=pBuffer;
/* init crcTmp */
crc_init(&crcTmp);
for (i = 0; i < length; i++){
crc_accumulate(*pTmp++, &crcTmp);
}
/* This is currently not needed, as only the checksum over payload should be computed
tmp = crcTmp;
crcAccumulate((unsigned char)(~crcTmp & 0xff),&tmp);
crcAccumulate((unsigned char)((~crcTmp>>8)&0xff),&tmp);
*checkConst = tmp;
*/
return(crcTmp);
}
/**
* @brief Calculates the X.25 checksum on a msg buffer
*
* @param pMSG buffer containing the msg to hash
* @param length number of bytes to hash
* @return the checksum over the buffer bytes
**/
static inline uint16_t crc_calculate_msg(mavlink_message_t* pMSG, int length)
{
// For a "message" of length bytes contained in the unsigned char array
// pointed to by pBuffer, calculate the CRC
// crcCalculate(unsigned char* pBuffer, int length, unsigned short* checkConst) < not needed
uint16_t crcTmp;
//uint16_t tmp;
uint8_t* pTmp;
int i;
pTmp=&pMSG->len;
/* init crcTmp */
crc_init(&crcTmp);
for (i = 0; i < 5; i++){
crc_accumulate(*pTmp++, &crcTmp);
while (length--) {
crc_accumulate(*pBuffer++, &crcTmp);
}
pTmp=&pMSG->payload[0];
for (; i < length; i++){
crc_accumulate(*pTmp++, &crcTmp);
}
/* This is currently not needed, as only the checksum over payload should be computed
tmp = crcTmp;
crcAccumulate((unsigned char)(~crcTmp & 0xff),&tmp);
crcAccumulate((unsigned char)((~crcTmp>>8)&0xff),&tmp);
*checkConst = tmp;
*/
return(crcTmp);
return crcTmp;
}
......
This diff is collapsed.
/** @file
* @brief MAVLink comm protocol testsuite generated from common.xml
* @see http://qgroundcontrol.org/mavlink/
* Generated on Wed Aug 24 17:14:16 2011
*/
#ifndef COMMON_TESTSUITE_H
#define COMMON_TESTSUITE_H
#ifdef __cplusplus
extern "C" {
#endif
static void mavtest_generate_outputs(mavlink_channel_t chan)
{
mavlink_msg_heartbeat_send(chan , 5 , 72 , 139 , 206 , 17 , 84 , 151 );
mavlink_msg_sys_status_send(chan , 17235 , 17339 , 17443 , 17547 , 17651 , 17755 , 17859 , 199 , 17963 , 18067 , 18171 , 18275 );
mavlink_msg_system_time_send(chan , 9223372036854775807 , 963497880 );
mavlink_msg_system_time_utc_send(chan , 963497464 , 963497672 );
mavlink_msg_ping_send(chan , 963497880 , 41 , 108 , 9223372036854775807 );
mavlink_msg_change_operator_control_send(chan , 5 , 72 , 139 , "AQGWMCSIYOEUKAQGWMCSIYOEU" );
mavlink_msg_change_operator_control_ack_send(chan , 5 , 72 , 139 );
mavlink_msg_auth_key_send(chan , "ARIZQHYPGXOFWNEVMDULCTKBSJARIZQH" );
mavlink_msg_set_mode_send(chan , 5 , 72 );
mavlink_msg_set_flight_mode_send(chan , 5 , 72 );
mavlink_msg_set_safety_mode_send(chan , 5 , 72 );
mavlink_msg_param_request_read_send(chan , 139 , 206 , "AHOVCJQXELSZGNUB" , 17235 );
mavlink_msg_param_request_list_send(chan , 5 , 72 );
mavlink_msg_param_value_send(chan , "AXUROLIFCZWTQNKH" , 17.0 , 77 , 17443 , 17547 );
mavlink_msg_param_set_send(chan , 17 , 84 , "APETIXMBQFUJYNCR" , 17.0 , 199 );
mavlink_msg_gps_raw_int_send(chan , 9223372036854775807 , 89 , 963497880 , 963498088 , 963498296 , 18275 , 18379 , 18483 , 18587 , 156 );
mavlink_msg_scaled_imu_send(chan , 9223372036854775807 , 17651 , 17755 , 17859 , 17963 , 18067 , 18171 , 18275 , 18379 , 18483 );
mavlink_msg_gps_status_send(chan , 5 , "72" , "132" , "192" , "252" , "56" );
mavlink_msg_raw_imu_send(chan , 9223372036854775807 , 17651 , 17755 , 17859 , 17963 , 18067 , 18171 , 18275 , 18379 , 18483 );
mavlink_msg_raw_pressure_send(chan , 9223372036854775807 , 17651 , 17755 , 17859 , 17963 );
mavlink_msg_scaled_pressure_send(chan , 9223372036854775807 , 73.0 , 101.0 , 18067 );
mavlink_msg_attitude_send(chan , 9223372036854775807 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 );
mavlink_msg_local_position_send(chan , 9223372036854775807 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 );
mavlink_msg_global_position_send(chan , 9223372036854775807 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 );
mavlink_msg_gps_raw_send(chan , 9223372036854775807 , 113 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 , 241.0 , 180 );
mavlink_msg_rc_channels_raw_send(chan , 17235 , 17339 , 17443 , 17547 , 17651 , 17755 , 17859 , 17963 , 53 );
mavlink_msg_rc_channels_scaled_send(chan , 17235 , 17339 , 17443 , 17547 , 17651 , 17755 , 17859 , 17963 , 53 );
mavlink_msg_servo_output_raw_send(chan , 17235 , 17339 , 17443 , 17547 , 17651 , 17755 , 17859 , 17963 );
mavlink_msg_waypoint_send(chan , 223 , 34 , 18691 , 101 , 168 , 235 , 46 , 17.0 , 45.0 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 );
mavlink_msg_waypoint_request_send(chan , 139 , 206 , 17235 );
mavlink_msg_waypoint_set_current_send(chan , 139 , 206 , 17235 );
mavlink_msg_waypoint_current_send(chan , 17235 );
mavlink_msg_waypoint_request_list_send(chan , 5 , 72 );
mavlink_msg_waypoint_count_send(chan , 139 , 206 , 17235 );
mavlink_msg_waypoint_clear_all_send(chan , 5 , 72 );
mavlink_msg_waypoint_reached_send(chan , 17235 );
mavlink_msg_waypoint_ack_send(chan , 5 , 72 , 139 );
mavlink_msg_gps_set_global_origin_send(chan , 41 , 108 , 963497464 , 963497672 , 963497880 );
mavlink_msg_gps_local_origin_set_send(chan , 963497464 , 963497672 , 963497880 );
mavlink_msg_local_position_setpoint_set_send(chan , 53 , 120 , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_local_position_setpoint_send(chan , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_global_position_setpoint_int_send(chan , 963497464 , 963497672 , 963497880 , 17859 );
mavlink_msg_safety_set_allowed_area_send(chan , 77 , 144 , 211 , 17.0 , 45.0 , 73.0 , 101.0 , 129.0 , 157.0 );
mavlink_msg_safety_allowed_area_send(chan , 77 , 17.0 , 45.0 , 73.0 , 101.0 , 129.0 , 157.0 );
mavlink_msg_set_roll_pitch_yaw_thrust_send(chan , 53 , 120 , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(chan , 53 , 120 , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(chan , 963497464 , 45.0 , 73.0 , 101.0 , 129.0 );
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(chan , 963497464 , 45.0 , 73.0 , 101.0 , 129.0 );
mavlink_msg_nav_controller_output_send(chan , 17.0 , 45.0 , 18275 , 18379 , 18483 , 73.0 , 101.0 , 129.0 );
mavlink_msg_position_target_send(chan , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_state_correction_send(chan , 17.0 , 45.0 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 , 241.0 );
mavlink_msg_request_data_stream_send(chan , 139 , 206 , 17 , 17235 , 84 );
mavlink_msg_data_stream_send(chan , 139 , 17235 , 206 );
mavlink_msg_manual_control_send(chan , 53 , 17.0 , 45.0 , 73.0 , 101.0 , 120 , 187 , 254 , 65 );
mavlink_msg_rc_channels_override_send(chan , 53 , 120 , 17235 , 17339 , 17443 , 17547 , 17651 , 17755 , 17859 , 17963 );
mavlink_msg_global_position_int_send(chan , 963497464 , 963497672 , 963497880 , 17859 , 17963 , 18067 , 18171 );
mavlink_msg_vfr_hud_send(chan , 17.0 , 45.0 , 18067 , 18171 , 73.0 , 101.0 );
mavlink_msg_command_short_send(chan , 53 , 120 , 187 , 254 , 17.0 , 45.0 , 73.0 , 101.0 );
mavlink_msg_command_long_send(chan , 89 , 156 , 223 , 34 , 17.0 , 45.0 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 );
mavlink_msg_command_ack_send(chan , 17.0 , 45.0 );
mavlink_msg_hil_state_send(chan , 9223372036854775807 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 , 963499128 , 963499336 , 963499544 , 19523 , 19627 , 19731 , 19835 , 19939 , 20043 );
mavlink_msg_hil_controls_send(chan , 9223372036854775807 , 73.0 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 , 241.0 , 269.0 , 125 , 192 );
mavlink_msg_hil_rc_inputs_raw_send(chan , 9223372036854775807 , 17651 , 17755 , 17859 , 17963 , 18067 , 18171 , 18275 , 18379 , 18483 , 18587 , 18691 , 18795 , 101 );
mavlink_msg_optical_flow_send(chan , 9223372036854775807 , 53 , 17859 , 17963 , 120 , 73.0 );
mavlink_msg_memory_vect_send(chan , 17235 , 139 , 206 , "17" );
mavlink_msg_debug_vect_send(chan , "ATMFYRKDWP" , 9223372036854775807 , 73.0 , 101.0 , 129.0 );
mavlink_msg_named_value_float_send(chan , "AHOVCJQXEL" , 17.0 );
mavlink_msg_named_value_int_send(chan , "AHOVCJQXEL" , 963497464 );
mavlink_msg_statustext_send(chan , 5 , "AIQYGOWEMUCKSAIQYGOWEMUCKSAIQYGOWEMUCKSAIQYGOWEMUC" );
mavlink_msg_debug_send(chan , 17 , 17.0 );
}
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // COMMON_TESTSUITE_H
/** @file
* @brief MAVLink comm protocol.
* @brief MAVLink comm protocol built from common.xml
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Saturday, August 20 2011, 14:34 UTC
* Generated on Fri Aug 26 14:04:08 2011
*/
#ifndef MAVLINK_H
#define MAVLINK_H
#pragma pack(push,1)
#include "mavlink_options.h"
#include "common.h"
#ifdef MAVLINK_DATA
#include "mavlink_data.h"
#ifndef MAVLINK_STX
#define MAVLINK_STX 254
#endif
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
#endif
#pragma pack(pop)
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 1
#endif
#include "version.h"
#include "common.h"
#endif // MAVLINK_H
// MESSAGE AUTH_KEY PACKING
#define MAVLINK_MSG_ID_AUTH_KEY 7
#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32
#define MAVLINK_MSG_7_LEN 32
#define MAVLINK_MSG_ID_AUTH_KEY_KEY 0xBA
#define MAVLINK_MSG_7_KEY 0xBA
typedef struct __mavlink_auth_key_t
typedef struct __mavlink_auth_key_t
{
char key[32]; ///< key
char key[32]; ///< key
} mavlink_auth_key_t;
#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32
#define MAVLINK_MSG_ID_7_LEN 32
#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32
#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \
"AUTH_KEY", \
1, \
{ { "key", MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
} \
}
/**
* @brief Pack a auth_key message
* @param system_id ID of this system
......@@ -22,18 +29,18 @@ typedef struct __mavlink_auth_key_t
* @param key key
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* key)
static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *key)
{
mavlink_auth_key_t *p = (mavlink_auth_key_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
memcpy(p->key, key, sizeof(p->key)); // char[32]:key
put_char_array_by_index(msg, 0, key, 32); // key
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN);
return mavlink_finalize_message(msg, system_id, component_id, 32, 119);
}
/**
* @brief Pack a auth_key message
* @brief Pack a auth_key message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
......@@ -41,16 +48,38 @@ static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t comp
* @param key key
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* key)
static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *key)
{
mavlink_auth_key_t *p = (mavlink_auth_key_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
memcpy(p->key, key, sizeof(p->key)); // char[32]:key
put_char_array_by_index(msg, 0, key, 32); // key
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 119);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Pack a auth_key message on a channel and send
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param key key
*/
static inline void mavlink_msg_auth_key_pack_chan_send(mavlink_channel_t chan,
mavlink_message_t* msg,
const char *key)
{
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
put_char_array_by_index(msg, 0, key, 32); // key
mavlink_finalize_message_chan_send(msg, chan, 32, 119);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Encode a auth_key struct into a message
*
......@@ -64,54 +93,33 @@ static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t co
return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a auth_key message
* @param chan MAVLink channel to send the message
*
* @param key key
*/
static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char* key)
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key)
{
mavlink_header_t hdr;
mavlink_auth_key_t payload;
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_AUTH_KEY_LEN )
memcpy(payload.key, key, sizeof(payload.key)); // char[32]:key
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_AUTH_KEY_LEN;
hdr.msgid = MAVLINK_MSG_ID_AUTH_KEY;
hdr.sysid = mavlink_system.sysid;
hdr.compid = mavlink_system.compid;
hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
mavlink_send_mem(chan, (uint8_t *)&payload, sizeof(payload) );
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0xBA, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
MAVLINK_ALIGNED_MESSAGE(msg, 32);
mavlink_msg_auth_key_pack_chan_send(chan, msg, key);
}
#endif
// MESSAGE AUTH_KEY UNPACKING
/**
* @brief Get field key from auth_key message
*
* @return key
*/
static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char* key)
static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key)
{
mavlink_auth_key_t *p = (mavlink_auth_key_t *)&msg->payload[0];
memcpy(key, p->key, sizeof(p->key));
return sizeof(p->key);
return MAVLINK_MSG_RETURN_char_array(msg, key, 32, 0);
}
/**
......@@ -122,5 +130,9 @@ static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg
*/
static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key)
{
memcpy( auth_key, msg->payload, sizeof(mavlink_auth_key_t));
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_auth_key_get_key(msg, auth_key->key);
#else
memcpy(auth_key, MAVLINK_PAYLOAD(msg), 32);
#endif
}
// MESSAGE BOOT PACKING
#define MAVLINK_MSG_ID_BOOT 1
#define MAVLINK_MSG_ID_BOOT_LEN 4
#define MAVLINK_MSG_1_LEN 4
#define MAVLINK_MSG_ID_BOOT_KEY 0xF9
#define MAVLINK_MSG_1_KEY 0xF9
typedef struct __mavlink_boot_t
typedef struct __mavlink_boot_t
{
uint32_t version; ///< The onboard software version
uint32_t version; ///< The onboard software version
} mavlink_boot_t;
/**
......@@ -21,18 +16,18 @@ typedef struct __mavlink_boot_t
* @param version The onboard software version
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t version)
static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t version)
{
mavlink_boot_t *p = (mavlink_boot_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_BOOT;
p->version = version; // uint32_t:The onboard software version
put_uint32_t_by_index(version, 0, msg->payload); // The onboard software version
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BOOT_LEN);
return mavlink_finalize_message(msg, system_id, component_id, 4, 61);
}
/**
* @brief Pack a boot message
* @brief Pack a boot message on a channel
* @param system_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
......@@ -40,16 +35,38 @@ static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t componen
* @param version The onboard software version
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_boot_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t version)
static inline uint16_t mavlink_msg_boot_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t version)
{
mavlink_boot_t *p = (mavlink_boot_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_BOOT;
p->version = version; // uint32_t:The onboard software version
put_uint32_t_by_index(version, 0, msg->payload); // The onboard software version
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BOOT_LEN);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 61);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Pack a boot message on a channel and send
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param version The onboard software version
*/
static inline void mavlink_msg_boot_pack_chan_send(mavlink_channel_t chan,
mavlink_message_t* msg,
uint32_t version)
{
msg->msgid = MAVLINK_MSG_ID_BOOT;
put_uint32_t_by_index(version, 0, msg->payload); // The onboard software version
mavlink_finalize_message_chan_send(msg, chan, 4, 61);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Encode a boot struct into a message
*
......@@ -63,43 +80,25 @@ static inline uint16_t mavlink_msg_boot_encode(uint8_t system_id, uint8_t compon
return mavlink_msg_boot_pack(system_id, component_id, msg, boot->version);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a boot message
* @param chan MAVLink channel to send the message
*
* @param version The onboard software version
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_boot_send(mavlink_channel_t chan, uint32_t version)
{
mavlink_header_t hdr;
mavlink_boot_t payload;
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_BOOT_LEN )
payload.version = version; // uint32_t:The onboard software version
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_BOOT_LEN;
hdr.msgid = MAVLINK_MSG_ID_BOOT;
hdr.sysid = mavlink_system.sysid;
hdr.compid = mavlink_system.compid;
hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
mavlink_send_mem(chan, (uint8_t *)&payload, sizeof(payload) );
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0xF9, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
MAVLINK_ALIGNED_MESSAGE(msg, 4);
mavlink_msg_boot_pack_chan_send(chan, msg, version);
}
#endif
// MESSAGE BOOT UNPACKING
/**
* @brief Get field version from boot message
*
......@@ -107,8 +106,7 @@ static inline void mavlink_msg_boot_send(mavlink_channel_t chan, uint32_t versio
*/
static inline uint32_t mavlink_msg_boot_get_version(const mavlink_message_t* msg)
{
mavlink_boot_t *p = (mavlink_boot_t *)&msg->payload[0];
return (uint32_t)(p->version);
return MAVLINK_MSG_RETURN_uint32_t(msg, 0);
}
/**
......@@ -119,5 +117,9 @@ static inline uint32_t mavlink_msg_boot_get_version(const mavlink_message_t* msg
*/
static inline void mavlink_msg_boot_decode(const mavlink_message_t* msg, mavlink_boot_t* boot)
{
memcpy( boot, msg->payload, sizeof(mavlink_boot_t));
#if MAVLINK_NEED_BYTE_SWAP
boot->version = mavlink_msg_boot_get_version(msg);
#else
memcpy(boot, msg->payload, 4);
#endif
}
// MESSAGE COMMAND_ACK PACKING
#define MAVLINK_MSG_ID_COMMAND_ACK 77
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 8
#define MAVLINK_MSG_77_LEN 8
#define MAVLINK_MSG_ID_COMMAND_ACK_KEY 0x16
#define MAVLINK_MSG_77_KEY 0x16
typedef struct __mavlink_command_ack_t
typedef struct __mavlink_command_ack_t
{
float command; ///< Current airspeed in m/s
float result; ///< 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
float command; ///< Current airspeed in m/s
float result; ///< 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
} mavlink_command_ack_t;
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 8
#define MAVLINK_MSG_ID_77_LEN 8
#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) }, \
} \
}
/**
* @brief Pack a command_ack message
* @param system_id ID of this system
......@@ -23,19 +32,19 @@ typedef struct __mavlink_command_ack_t
* @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float command, float result)
static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float command, float result)
{
mavlink_command_ack_t *p = (mavlink_command_ack_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
p->command = command; // float:Current airspeed in m/s
p->result = result; // float:1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
put_float_by_index(msg, 0, command); // Current airspeed in m/s
put_float_by_index(msg, 4, result); // 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
return mavlink_finalize_message(msg, system_id, component_id, 8, 8);
}
/**
* @brief Pack a command_ack message
* @brief Pack a command_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
......@@ -44,16 +53,40 @@ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t c
* @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float command, float result)
static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float command,float result)
{
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
put_float_by_index(msg, 0, command); // Current airspeed in m/s
put_float_by_index(msg, 4, result); // 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 8);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Pack a command_ack message on a channel and send
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param command Current airspeed in m/s
* @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
*/
static inline void mavlink_msg_command_ack_pack_chan_send(mavlink_channel_t chan,
mavlink_message_t* msg,
float command,float result)
{
mavlink_command_ack_t *p = (mavlink_command_ack_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
p->command = command; // float:Current airspeed in m/s
p->result = result; // float:1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
put_float_by_index(msg, 0, command); // Current airspeed in m/s
put_float_by_index(msg, 4, result); // 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
mavlink_finalize_message_chan_send(msg, chan, 8, 8);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Encode a command_ack struct into a message
......@@ -68,8 +101,6 @@ static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t
return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a command_ack message
* @param chan MAVLink channel to send the message
......@@ -77,36 +108,19 @@ static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t
* @param command Current airspeed in m/s
* @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, float command, float result)
{
mavlink_header_t hdr;
mavlink_command_ack_t payload;
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN )
payload.command = command; // float:Current airspeed in m/s
payload.result = result; // float:1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_COMMAND_ACK_LEN;
hdr.msgid = MAVLINK_MSG_ID_COMMAND_ACK;
hdr.sysid = mavlink_system.sysid;
hdr.compid = mavlink_system.compid;
hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
mavlink_send_mem(chan, (uint8_t *)&payload, sizeof(payload) );
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0x16, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
MAVLINK_ALIGNED_MESSAGE(msg, 8);
mavlink_msg_command_ack_pack_chan_send(chan, msg, command, result);
}
#endif
// MESSAGE COMMAND_ACK UNPACKING
/**
* @brief Get field command from command_ack message
*
......@@ -114,8 +128,7 @@ static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, float co
*/
static inline float mavlink_msg_command_ack_get_command(const mavlink_message_t* msg)
{
mavlink_command_ack_t *p = (mavlink_command_ack_t *)&msg->payload[0];
return (float)(p->command);
return MAVLINK_MSG_RETURN_float(msg, 0);
}
/**
......@@ -125,8 +138,7 @@ static inline float mavlink_msg_command_ack_get_command(const mavlink_message_t*
*/
static inline float mavlink_msg_command_ack_get_result(const mavlink_message_t* msg)
{
mavlink_command_ack_t *p = (mavlink_command_ack_t *)&msg->payload[0];
return (float)(p->result);
return MAVLINK_MSG_RETURN_float(msg, 4);
}
/**
......@@ -137,5 +149,10 @@ static inline float mavlink_msg_command_ack_get_result(const mavlink_message_t*
*/
static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack)
{
memcpy( command_ack, msg->payload, sizeof(mavlink_command_ack_t));
#if MAVLINK_NEED_BYTE_SWAP
command_ack->command = mavlink_msg_command_ack_get_command(msg);
command_ack->result = mavlink_msg_command_ack_get_result(msg);
#else
memcpy(command_ack, MAVLINK_PAYLOAD(msg), 8);
#endif
}
// MESSAGE DATA_STREAM PACKING
#define MAVLINK_MSG_ID_DATA_STREAM 67
#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4
#define MAVLINK_MSG_67_LEN 4
#define MAVLINK_MSG_ID_DATA_STREAM_KEY 0x50
#define MAVLINK_MSG_67_KEY 0x50
typedef struct __mavlink_data_stream_t
typedef struct __mavlink_data_stream_t
{
uint16_t message_rate; ///< The requested interval between two messages of this type
uint8_t stream_id; ///< The ID of the requested data stream
uint8_t on_off; ///< 1 stream is enabled, 0 stream is stopped.
uint16_t message_rate; ///< The requested interval between two messages of this type
uint8_t stream_id; ///< The ID of the requested data stream
uint8_t on_off; ///< 1 stream is enabled, 0 stream is stopped.
} mavlink_data_stream_t;
#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4
#define MAVLINK_MSG_ID_67_LEN 4
#define MAVLINK_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) }, \
} \
}
/**
* @brief Pack a data_stream message
* @param system_id ID of this system
......@@ -25,20 +35,20 @@ typedef struct __mavlink_data_stream_t
* @param on_off 1 stream is enabled, 0 stream is stopped.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
{
mavlink_data_stream_t *p = (mavlink_data_stream_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM;
p->stream_id = stream_id; // uint8_t:The ID of the requested data stream
p->message_rate = message_rate; // uint16_t:The requested interval between two messages of this type
p->on_off = on_off; // uint8_t:1 stream is enabled, 0 stream is stopped.
put_uint16_t_by_index(msg, 0, message_rate); // The requested interval between two messages of this type
put_uint8_t_by_index(msg, 2, stream_id); // The ID of the requested data stream
put_uint8_t_by_index(msg, 3, on_off); // 1 stream is enabled, 0 stream is stopped.
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN);
return mavlink_finalize_message(msg, system_id, component_id, 4, 21);
}
/**
* @brief Pack a data_stream message
* @brief Pack a data_stream message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
......@@ -48,18 +58,44 @@ static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t c
* @param on_off 1 stream is enabled, 0 stream is stopped.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t stream_id,uint16_t message_rate,uint8_t on_off)
{
mavlink_data_stream_t *p = (mavlink_data_stream_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM;
p->stream_id = stream_id; // uint8_t:The ID of the requested data stream
p->message_rate = message_rate; // uint16_t:The requested interval between two messages of this type
p->on_off = on_off; // uint8_t:1 stream is enabled, 0 stream is stopped.
put_uint16_t_by_index(msg, 0, message_rate); // The requested interval between two messages of this type
put_uint8_t_by_index(msg, 2, stream_id); // The ID of the requested data stream
put_uint8_t_by_index(msg, 3, on_off); // 1 stream is enabled, 0 stream is stopped.
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 21);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Pack a data_stream message on a channel and send
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param stream_id The ID of the requested data stream
* @param message_rate The requested interval between two messages of this type
* @param on_off 1 stream is enabled, 0 stream is stopped.
*/
static inline void mavlink_msg_data_stream_pack_chan_send(mavlink_channel_t chan,
mavlink_message_t* msg,
uint8_t stream_id,uint16_t message_rate,uint8_t on_off)
{
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM;
put_uint16_t_by_index(msg, 0, message_rate); // The requested interval between two messages of this type
put_uint8_t_by_index(msg, 2, stream_id); // The ID of the requested data stream
put_uint8_t_by_index(msg, 3, on_off); // 1 stream is enabled, 0 stream is stopped.
mavlink_finalize_message_chan_send(msg, chan, 4, 21);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Encode a data_stream struct into a message
*
......@@ -73,8 +109,6 @@ static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t
return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a data_stream message
* @param chan MAVLink channel to send the message
......@@ -83,37 +117,19 @@ static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t
* @param message_rate The requested interval between two messages of this type
* @param on_off 1 stream is enabled, 0 stream is stopped.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
{
mavlink_header_t hdr;
mavlink_data_stream_t payload;
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_DATA_STREAM_LEN )
payload.stream_id = stream_id; // uint8_t:The ID of the requested data stream
payload.message_rate = message_rate; // uint16_t:The requested interval between two messages of this type
payload.on_off = on_off; // uint8_t:1 stream is enabled, 0 stream is stopped.
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_DATA_STREAM_LEN;
hdr.msgid = MAVLINK_MSG_ID_DATA_STREAM;
hdr.sysid = mavlink_system.sysid;
hdr.compid = mavlink_system.compid;
hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
mavlink_send_mem(chan, (uint8_t *)&payload, sizeof(payload) );
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0x50, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
MAVLINK_ALIGNED_MESSAGE(msg, 4);
mavlink_msg_data_stream_pack_chan_send(chan, msg, stream_id, message_rate, on_off);
}
#endif
// MESSAGE DATA_STREAM UNPACKING
/**
* @brief Get field stream_id from data_stream message
*
......@@ -121,8 +137,7 @@ static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t
*/
static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg)
{
mavlink_data_stream_t *p = (mavlink_data_stream_t *)&msg->payload[0];
return (uint8_t)(p->stream_id);
return MAVLINK_MSG_RETURN_uint8_t(msg, 2);
}
/**
......@@ -132,8 +147,7 @@ static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_messag
*/
static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg)
{
mavlink_data_stream_t *p = (mavlink_data_stream_t *)&msg->payload[0];
return (uint16_t)(p->message_rate);
return MAVLINK_MSG_RETURN_uint16_t(msg, 0);
}
/**
......@@ -143,8 +157,7 @@ static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_me
*/
static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg)
{
mavlink_data_stream_t *p = (mavlink_data_stream_t *)&msg->payload[0];
return (uint8_t)(p->on_off);
return MAVLINK_MSG_RETURN_uint8_t(msg, 3);
}
/**
......@@ -155,5 +168,11 @@ static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t
*/
static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, mavlink_data_stream_t* data_stream)
{
memcpy( data_stream, msg->payload, sizeof(mavlink_data_stream_t));
#if MAVLINK_NEED_BYTE_SWAP
data_stream->message_rate = mavlink_msg_data_stream_get_message_rate(msg);
data_stream->stream_id = mavlink_msg_data_stream_get_stream_id(msg);
data_stream->on_off = mavlink_msg_data_stream_get_on_off(msg);
#else
memcpy(data_stream, MAVLINK_PAYLOAD(msg), 4);
#endif
}
// MESSAGE DEBUG PACKING
#define MAVLINK_MSG_ID_DEBUG 255
#define MAVLINK_MSG_ID_DEBUG_LEN 5
#define MAVLINK_MSG_255_LEN 5
#define MAVLINK_MSG_ID_DEBUG_KEY 0x54
#define MAVLINK_MSG_255_KEY 0x54
typedef struct __mavlink_debug_t
typedef struct __mavlink_debug_t
{
float value; ///< DEBUG value
uint8_t ind; ///< index of debug variable
float value; ///< DEBUG value
uint8_t ind; ///< index of debug variable
} mavlink_debug_t;
#define MAVLINK_MSG_ID_DEBUG_LEN 5
#define MAVLINK_MSG_ID_255_LEN 5
#define MAVLINK_MESSAGE_INFO_DEBUG { \
"DEBUG", \
2, \
{ { "value", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_debug_t, value) }, \
{ "ind", MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_debug_t, ind) }, \
} \
}
/**
* @brief Pack a debug message
* @param system_id ID of this system
......@@ -23,19 +32,19 @@ typedef struct __mavlink_debug_t
* @param value DEBUG value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t ind, float value)
static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t ind, float value)
{
mavlink_debug_t *p = (mavlink_debug_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_DEBUG;
p->ind = ind; // uint8_t:index of debug variable
p->value = value; // float:DEBUG value
put_float_by_index(msg, 0, value); // DEBUG value
put_uint8_t_by_index(msg, 4, ind); // index of debug variable
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN);
return mavlink_finalize_message(msg, system_id, component_id, 5, 127);
}
/**
* @brief Pack a debug message
* @brief Pack a debug message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
......@@ -44,16 +53,40 @@ static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t compone
* @param value DEBUG value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t ind, float value)
static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t ind,float value)
{
msg->msgid = MAVLINK_MSG_ID_DEBUG;
put_float_by_index(msg, 0, value); // DEBUG value
put_uint8_t_by_index(msg, 4, ind); // index of debug variable
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 5, 127);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Pack a debug message on a channel and send
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param ind index of debug variable
* @param value DEBUG value
*/
static inline void mavlink_msg_debug_pack_chan_send(mavlink_channel_t chan,
mavlink_message_t* msg,
uint8_t ind,float value)
{
mavlink_debug_t *p = (mavlink_debug_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_DEBUG;
p->ind = ind; // uint8_t:index of debug variable
p->value = value; // float:DEBUG value
put_float_by_index(msg, 0, value); // DEBUG value
put_uint8_t_by_index(msg, 4, ind); // index of debug variable
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN);
mavlink_finalize_message_chan_send(msg, chan, 5, 127);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Encode a debug struct into a message
......@@ -68,8 +101,6 @@ static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t compo
return mavlink_msg_debug_pack(system_id, component_id, msg, debug->ind, debug->value);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a debug message
* @param chan MAVLink channel to send the message
......@@ -77,36 +108,19 @@ static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t compo
* @param ind index of debug variable
* @param value DEBUG value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, float value)
{
mavlink_header_t hdr;
mavlink_debug_t payload;
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_DEBUG_LEN )
payload.ind = ind; // uint8_t:index of debug variable
payload.value = value; // float:DEBUG value
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_DEBUG_LEN;
hdr.msgid = MAVLINK_MSG_ID_DEBUG;
hdr.sysid = mavlink_system.sysid;
hdr.compid = mavlink_system.compid;
hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
mavlink_send_mem(chan, (uint8_t *)&payload, sizeof(payload) );
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0x54, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
MAVLINK_ALIGNED_MESSAGE(msg, 5);
mavlink_msg_debug_pack_chan_send(chan, msg, ind, value);
}
#endif
// MESSAGE DEBUG UNPACKING
/**
* @brief Get field ind from debug message
*
......@@ -114,8 +128,7 @@ static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, f
*/
static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg)
{
mavlink_debug_t *p = (mavlink_debug_t *)&msg->payload[0];
return (uint8_t)(p->ind);
return MAVLINK_MSG_RETURN_uint8_t(msg, 4);
}
/**
......@@ -125,8 +138,7 @@ static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg)
*/
static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
{
mavlink_debug_t *p = (mavlink_debug_t *)&msg->payload[0];
return (float)(p->value);
return MAVLINK_MSG_RETURN_float(msg, 0);
}
/**
......@@ -137,5 +149,10 @@ static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
*/
static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug)
{
memcpy( debug, msg->payload, sizeof(mavlink_debug_t));
#if MAVLINK_NEED_BYTE_SWAP
debug->value = mavlink_msg_debug_get_value(msg);
debug->ind = mavlink_msg_debug_get_ind(msg);
#else
memcpy(debug, MAVLINK_PAYLOAD(msg), 5);
#endif
}
// MESSAGE DEBUG_VECT PACKING
#define MAVLINK_MSG_ID_DEBUG_VECT 251
#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
#define MAVLINK_MSG_251_LEN 30
#define MAVLINK_MSG_ID_DEBUG_VECT_KEY 0x2B
#define MAVLINK_MSG_251_KEY 0x2B
typedef struct __mavlink_debug_vect_t
typedef struct __mavlink_debug_vect_t
{
uint64_t usec; ///< Timestamp
float x; ///< x
float y; ///< y
float z; ///< z
char name[10]; ///< Name
uint64_t usec; ///< Timestamp
float x; ///< x
float y; ///< y
float z; ///< z
char name[10]; ///< Name
} mavlink_debug_vect_t;
#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
#define MAVLINK_MSG_ID_251_LEN 30
#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
"DEBUG_VECT", \
5, \
{ { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, 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) }, \
} \
}
/**
* @brief Pack a debug_vect message
* @param system_id ID of this system
......@@ -30,22 +41,22 @@ typedef struct __mavlink_debug_vect_t
* @param z z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, uint64_t usec, float x, float y, float z)
static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *name, uint64_t usec, float x, float y, float z)
{
mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
memcpy(p->name, name, sizeof(p->name)); // char[10]:Name
p->usec = usec; // uint64_t:Timestamp
p->x = x; // float:x
p->y = y; // float:y
p->z = z; // float:z
put_uint64_t_by_index(msg, 0, usec); // Timestamp
put_float_by_index(msg, 8, x); // x
put_float_by_index(msg, 12, y); // y
put_float_by_index(msg, 16, z); // z
put_char_array_by_index(msg, 20, name, 10); // Name
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
return mavlink_finalize_message(msg, system_id, component_id, 30, 15);
}
/**
* @brief Pack a debug_vect message
* @brief Pack a debug_vect message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
......@@ -57,20 +68,50 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co
* @param z z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, uint64_t usec, float x, float y, float z)
static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *name,uint64_t usec,float x,float y,float z)
{
mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
memcpy(p->name, name, sizeof(p->name)); // char[10]:Name
p->usec = usec; // uint64_t:Timestamp
p->x = x; // float:x
p->y = y; // float:y
p->z = z; // float:z
put_uint64_t_by_index(msg, 0, usec); // Timestamp
put_float_by_index(msg, 8, x); // x
put_float_by_index(msg, 12, y); // y
put_float_by_index(msg, 16, z); // z
put_char_array_by_index(msg, 20, name, 10); // Name
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 15);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Pack a debug_vect message on a channel and send
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param name Name
* @param usec Timestamp
* @param x x
* @param y y
* @param z z
*/
static inline void mavlink_msg_debug_vect_pack_chan_send(mavlink_channel_t chan,
mavlink_message_t* msg,
const char *name,uint64_t usec,float x,float y,float z)
{
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
put_uint64_t_by_index(msg, 0, usec); // Timestamp
put_float_by_index(msg, 8, x); // x
put_float_by_index(msg, 12, y); // y
put_float_by_index(msg, 16, z); // z
put_char_array_by_index(msg, 20, name, 10); // Name
mavlink_finalize_message_chan_send(msg, chan, 30, 15);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Encode a debug_vect struct into a message
*
......@@ -84,8 +125,6 @@ static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t
return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Send a debug_vect message
* @param chan MAVLink channel to send the message
......@@ -96,50 +135,27 @@ static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t
* @param y y
* @param z z
*/
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char* name, uint64_t usec, float x, float y, float z)
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t usec, float x, float y, float z)
{
mavlink_header_t hdr;
mavlink_debug_vect_t payload;
MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN )
memcpy(payload.name, name, sizeof(payload.name)); // char[10]:Name
payload.usec = usec; // uint64_t:Timestamp
payload.x = x; // float:x
payload.y = y; // float:y
payload.z = z; // float:z
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_DEBUG_VECT_LEN;
hdr.msgid = MAVLINK_MSG_ID_DEBUG_VECT;
hdr.sysid = mavlink_system.sysid;
hdr.compid = mavlink_system.compid;
hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
mavlink_send_mem(chan, (uint8_t *)&payload, sizeof(payload) );
crc_init(&hdr.ck);
crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
crc_accumulate( 0x2B, &hdr.ck); /// include key in X25 checksum
mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
MAVLINK_BUFFER_CHECK_END
MAVLINK_ALIGNED_MESSAGE(msg, 30);
mavlink_msg_debug_vect_pack_chan_send(chan, msg, name, usec, x, y, z);
}
#endif
// MESSAGE DEBUG_VECT UNPACKING
/**
* @brief Get field name from debug_vect message
*
* @return Name
*/
static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char* name)
static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name)
{
mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
memcpy(name, p->name, sizeof(p->name));
return sizeof(p->name);
return MAVLINK_MSG_RETURN_char_array(msg, name, 10, 20);
}
/**
......@@ -149,8 +165,7 @@ static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t*
*/
static inline uint64_t mavlink_msg_debug_vect_get_usec(const mavlink_message_t* msg)
{
mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
return (uint64_t)(p->usec);
return MAVLINK_MSG_RETURN_uint64_t(msg, 0);
}
/**
......@@ -160,8 +175,7 @@ static inline uint64_t mavlink_msg_debug_vect_get_usec(const mavlink_message_t*
*/
static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
{
mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
return (float)(p->x);
return MAVLINK_MSG_RETURN_float(msg, 8);
}
/**
......@@ -171,8 +185,7 @@ static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
*/
static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
{
mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
return (float)(p->y);
return MAVLINK_MSG_RETURN_float(msg, 12);
}
/**
......@@ -182,8 +195,7 @@ static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
*/
static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
{
mavlink_debug_vect_t *p = (mavlink_debug_vect_t *)&msg->payload[0];
return (float)(p->z);
return MAVLINK_MSG_RETURN_float(msg, 16);
}
/**
......@@ -194,5 +206,13 @@ static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
*/
static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
{
memcpy( debug_vect, msg->payload, sizeof(mavlink_debug_vect_t));
#if MAVLINK_NEED_BYTE_SWAP
debug_vect->usec = mavlink_msg_debug_vect_get_usec(msg);
debug_vect->x = mavlink_msg_debug_vect_get_x(msg);
debug_vect->y = mavlink_msg_debug_vect_get_y(msg);
debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
#else
memcpy(debug_vect, MAVLINK_PAYLOAD(msg), 30);
#endif
}
This diff is collapsed.
/** @file
* @brief MAVLink comm protocol built from common.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Aug 27 10:06:32 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#include "mavlink.h"
#endif // MAVLINK_VERSION_H
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.
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.
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