Commit fe178f2a authored by James Goppert's avatar James Goppert

Updated mavlink.

parent 10f544c1
......@@ -115,7 +115,7 @@ else()
endif()
find_or_build_from_source(MAVLINK thirdParty/mavlink)
find_or_build_from_source(QSERIAL thirdParty/qserial)
find_or_build_from_source(QSERIALPORT thirdParty/qserialport)
# build libraries from source if not found on system
if(MAVLINK_BUILD_FROM_SOURCE)
......@@ -132,67 +132,67 @@ if(MAVLINK_BUILD_FROM_SOURCE)
COMMAND touch MAVLINK_BUILD.stamp)
endif()
if(QSERIAL_BUILD_FROM_SOURCE)
# qserial headers without Q_OBJECT
# r !grep -RL Q_OBJECT thirdParty/qserial/include
set (qserialHdrs
thirdParty/qserial/include/QtSerialPort/qserialport_export.h
thirdParty/qserial/include/QtSerialPort/QSerialPort
thirdParty/qserial/include/QtSerialPort/qportsettings.h
if(QSERIALPORT_BUILD_FROM_SOURCE)
# qserialport headers without Q_OBJECT
# r !grep -RL Q_OBJECT thirdParty/qserialport/include
set (qserialportHdrs
thirdParty/qserialport/include/QtSerialPort/qserialport_export.h
thirdParty/qserialport/include/QtSerialPort/qserialport
thirdParty/qserialport/include/QtSerialPort/qportsettings.h
)
# qserial headers with Q_OBJECT
# r !grep -Rl Q_OBJECT thirdParty/qserial
set (qserialMocSrc
thirdParty/qserial/include/QtSerialPort/qserialport.h
thirdParty/qserial/include/QtSerialPort/qserialportnative.h
# qserialport headers with Q_OBJECT
# r !grep -Rl Q_OBJECT thirdParty/qserialport
set (qserialportMocSrc
thirdParty/qserialport/include/QtSerialPort/qserialport.h
thirdParty/qserialport/include/QtSerialPort/qserialportnative.h
)
# qserial src
set (qserialSrc
thirdParty/qserial/src/common/qserialport.cpp
thirdParty/qserial/src/common/qportsettings.cpp
# qserialport src
set (qserialportSrc
thirdParty/qserialport/src/common/qserialport.cpp
thirdParty/qserialport/src/common/qportsettings.cpp
)
# qserial native code
# qserialport native code
if (WIN32)
list(APPEND qserialHdrs
thirdParty/qserial/src/win32/commdcbhelper.h
list(APPEND qserialportHdrs
thirdParty/qserialport/src/win32/commdcbhelper.h
)
list(APPEND qserialMocSrc
thirdParty/qserial/src/win32/qwincommevtnotifier.h
thirdParty/qserial/src/win32/wincommevtbreaker.h
list(APPEND qserialportMocSrc
thirdParty/qserialport/src/win32/qwincommevtnotifier.h
thirdParty/qserialport/src/win32/wincommevtbreaker.h
)
list(APPEND qserialSrc
thirdParty/qserial/src/win32/qserialportnative_win32.cpp
thirdParty/qserial/src/win32/commdcbhelper.cpp
thirdParty/qserial/src/win32/qwincommevtnotifier.cpp
#thirdParty/qserial/src/win32/qserialportnative_wince.cpp
#thirdParty/qserial/src/win32/wincommevtbreaker.cpp
list(APPEND qserialportSrc
thirdParty/qserialport/src/win32/qserialportnative_win32.cpp
thirdParty/qserialport/src/win32/commdcbhelper.cpp
thirdParty/qserialport/src/win32/qwincommevtnotifier.cpp
#thirdParty/qserialport/src/win32/qserialportnative_wince.cpp
#thirdParty/qserialport/src/win32/wincommevtbreaker.cpp
)
elseif(UNIX OR APPLE)
list(APPEND qserialHdrs
thirdParty/qserial/src/posix/termioshelper.h
list(APPEND qserialportHdrs
thirdParty/qserialport/src/posix/termioshelper.h
)
list(APPEND qserialSrc
thirdParty/qserial/src/posix/termioshelper.cpp
thirdParty/qserial/src/posix/qserialportnative_posix.cpp
list(APPEND qserialportSrc
thirdParty/qserialport/src/posix/termioshelper.cpp
thirdParty/qserialport/src/posix/qserialportnative_posix.cpp
)
else()
message(FATAL_ERROR "unknown OS")
endif()
# qserial linking
qt4_wrap_cpp(qserialMoc ${qserialMocSrc})
add_library(qserial ${qserialMoc} ${qserialSrc})
target_link_libraries(qserial ${QT_LIBRARIES})
# qserialport linking
qt4_wrap_cpp(qserialportMoc ${qserialportMocSrc})
add_library(qserialport ${qserialportMoc} ${qserialportSrc})
target_link_libraries(qserialport ${QT_LIBRARIES})
set(QSERIAL_INCLUDE_DIRS
${PROJECT_SOURCE_DIR}/thirdParty/qserial/include
${PROJECT_SOURCE_DIR}/thirdParty/qserial/include/QtSerialPort
${PROJECT_SOURCE_DIR}/thirdParty/qserial/src
set(QSERIALPORT_INCLUDE_DIRS
${PROJECT_SOURCE_DIR}/thirdParty/qserialport/include
${PROJECT_SOURCE_DIR}/thirdParty/qserialport/include/QtSerialPort
${PROJECT_SOURCE_DIR}/thirdParty/qserialport/src
)
set(QSERIAL_LIBRARIES qserial)
add_custom_command(OUTPUT QSERIAL_BUILD.stamp
COMMAND touch QSERIAL_BUILD.stamp)
set(QSERIALPORT_LIBRARIES qserialport)
add_custom_command(OUTPUT qserialport_BUILD.stamp
COMMAND touch qserialport_BUILD.stamp)
endif()
# data directory
......@@ -249,10 +249,10 @@ if (MAVLINK_FOUND)
list(APPEND qgroundcontrolIncludes ${MAVLINK_INCLUDE_DIRS})
endif()
message(STATUS "\t\tQSERIAL\t\t${QSERIAL_FOUND}")
if (QSERIAL_FOUND)
list(APPEND qgroundcontrolIncludes ${QSERIAL_INCLUDE_DIRS})
list(APPEND qgroundcontrolLibs ${QSERIAL_LIBRARIES})
message(STATUS "\t\tqserialport\t${QSERIALPORT_FOUND}")
if (QSERIALPORT_FOUND)
list(APPEND qgroundcontrolIncludes ${QSERIALPORT_INCLUDE_DIRS})
list(APPEND qgroundcontrolLibs ${QSERIALPORT_LIBRARIES})
endif()
message(STATUS "\t\tOpenSceneGraph\t${OPENSCENEGRAPH_FOUND}")
......
# - Try to find QSERIAL
# - Try to find QSERIALPORT
# Once done, this will define
#
# QSERIAL_FOUND - system has scicoslab
# QSERIAL_INCLUDE_DIRS - the scicoslab include directories
# QSERIAL_LIBRARIES - libraries to link to
# QSERIALPORT_FOUND - system has scicoslab
# QSERIALPORT_INCLUDE_DIRS - the scicoslab include directories
# QSERIALPORT_LIBRARIES - libraries to link to
include(LibFindMacros)
# Include dir
find_path(QSERIAL_INCLUDE_DIR
find_path(QSERIALPORT_INCLUDE_DIR
NAMES QSerialPort
PATHS
/usr/include/QtSerialPort
......@@ -17,7 +17,7 @@ find_path(QSERIAL_INCLUDE_DIR
)
# Finally the library itself
find_library(QSERIAL_LIBRARY
find_library(QSERIALPORT_LIBRARY
NAMES
QtSerialPort
PATHS
......@@ -28,6 +28,6 @@ find_library(QSERIAL_LIBRARY
# Set the include dir variables and the libraries and let libfind_process do the rest.
# NOTE: Singular variables for this library, plural for libraries this this lib depends on.
set(QSERIAL_PROCESS_INCLUDES QSERIAL_INCLUDE_DIR)
set(QSERIAL_PROCESS_LIBS QSERIAL_LIBRARY QSERIAL_LIBRARIES)
libfind_process(QSERIAL)
set(QSERIALPORT_PROCESS_INCLUDES QSERIALPORT_INCLUDE_DIR)
set(QSERIALPORT_PROCESS_LIBS QSERIALPORT_LIBRARY QSERIALPORT_LIBRARIES)
libfind_process(QSERIALPORT)
......@@ -390,14 +390,14 @@ void MAVLinkProtocol::sendHeartbeat()
mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, OCU, MAV_AUTOPILOT_GENERIC);
sendMessage(beat);
}
if (m_authEnabled) {
mavlink_message_t msg;
mavlink_auth_key_t auth;
if (m_authKey.length() != MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN) m_authKey.resize(MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN);
strcpy(auth.key, m_authKey.toStdString().c_str());
mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
sendMessage(msg);
}
//if (m_authEnabled) {
//mavlink_message_t msg;
//mavlink_auth_key_t auth;
//if (m_authKey.length() != MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN) m_authKey.resize(MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN);
//strcpy(auth.key, m_authKey.toStdString().c_str());
//mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
//sendMessage(msg);
//}
}
/** @param enabled true to enable heartbeats emission at heartbeatRate, false to disable */
......
......@@ -690,15 +690,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
break;
case MAVLINK_MSG_ID_SCALED_PRESSURE: {
mavlink_scaled_pressure_t pressure;
mavlink_msg_scaled_pressure_decode(&message, &pressure);
quint64 time = this->getUnixTime(pressure.usec);
emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time);
emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time);
}
break;
//case MAVLINK_MSG_ID_SCALED_PRESSURE: {
//mavlink_scaled_pressure_t pressure;
//mavlink_msg_scaled_pressure_decode(&message, &pressure);
//quint64 time = this->getUnixTime(pressure.usec);
//emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
//emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time);
//emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time);
//}
//break;
case MAVLINK_MSG_ID_RC_CHANNELS_RAW: {
mavlink_rc_channels_raw_t channels;
......@@ -1304,10 +1304,10 @@ void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDesc
uasState = tr("EMERGENCY");
stateDescription = tr("EMERGENCY: Land Immediately!");
break;
case MAV_STATE_HILSIM:
uasState = tr("HIL SIM");
stateDescription = tr("HIL Simulation, Sensors read from SIM");
break;
//case MAV_STATE_HILSIM:
//uasState = tr("HIL SIM");
//stateDescription = tr("HIL Simulation, Sensors read from SIM");
//break;
case MAV_STATE_POWEROFF:
uasState = tr("SHUTDOWN");
......@@ -1975,24 +1975,24 @@ bool UAS::emergencyKILL()
void UAS::startHil()
{
mavlink_message_t msg;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_START_HILSIM);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
//mavlink_message_t msg;
//// TODO Replace MG System ID with static function call and allow to change ID in GUI
//mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_START_HILSIM);
//// Send message twice to increase chance of reception
//sendMessage(msg);
//sendMessage(msg);
}
void UAS::stopHil()
{
mavlink_message_t msg;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_STOP_HILSIM);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
//mavlink_message_t msg;
//// TODO Replace MG System ID with static function call and allow to change ID in GUI
//mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_STOP_HILSIM);
//// Send message twice to increase chance of reception
//sendMessage(msg);
//sendMessage(msg);
}
......
......@@ -4,9 +4,11 @@ PS3='Please enter your choice: '
LIST="all mavlink qserialport end"
echo
echo this script grabs upstream releases
echo
function fetch_qserialport
{
echo
rm -rf qserialport
git clone git://gitorious.org/inbiza-labs/qserialport.git
rm -rf qserialport/.git
......@@ -14,8 +16,7 @@ function fetch_qserialport
function fetch_mavlink
{
echo you chose mavlink
echo fetching mavlink
echo
rm -rf mavlink
git clone git@github.com:openmav/mavlink.git
rm -rf mavlink/.git
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, February 15 2011, 15:57 UTC
* Generated on Thursday, March 31 2011, 22:06 UTC
*/
#ifndef ARDUPILOTMEGA_H
#define ARDUPILOTMEGA_H
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, February 15 2011, 15:57 UTC
* Generated on Thursday, March 31 2011, 22:06 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Wednesday, March 2 2011, 13:12 UTC
* Generated on Thursday, March 31 2011, 22:06 UTC
*/
#ifndef COMMON_H
#define COMMON_H
......@@ -87,6 +87,7 @@ enum MAV_DATA_STREAM
#include "./mavlink_msg_system_time_utc.h"
#include "./mavlink_msg_change_operator_control.h"
#include "./mavlink_msg_change_operator_control_ack.h"
#include "./mavlink_msg_auth_key.h"
#include "./mavlink_msg_action_ack.h"
#include "./mavlink_msg_action.h"
#include "./mavlink_msg_set_mode.h"
......@@ -100,6 +101,7 @@ enum MAV_DATA_STREAM
#include "./mavlink_msg_gps_status.h"
#include "./mavlink_msg_raw_imu.h"
#include "./mavlink_msg_raw_pressure.h"
#include "./mavlink_msg_scaled_pressure.h"
#include "./mavlink_msg_attitude.h"
#include "./mavlink_msg_local_position.h"
#include "./mavlink_msg_global_position.h"
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Wednesday, March 2 2011, 13:12 UTC
* Generated on Thursday, March 31 2011, 22:06 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
......@@ -6,9 +6,9 @@ typedef struct __mavlink_gps_set_global_origin_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint32_t latitude; ///< global position * 1E7
uint32_t longitude; ///< global position * 1E7
uint32_t altitude; ///< global position * 1000
int32_t latitude; ///< global position * 1E7
int32_t longitude; ///< global position * 1E7
int32_t altitude; ///< global position * 1000
} mavlink_gps_set_global_origin_t;
......@@ -27,16 +27,16 @@ typedef struct __mavlink_gps_set_global_origin_t
* @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint32_t latitude, uint32_t longitude, uint32_t altitude)
static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint32_t_by_index(latitude, i, msg->payload); // global position * 1E7
i += put_uint32_t_by_index(longitude, i, msg->payload); // global position * 1E7
i += put_uint32_t_by_index(altitude, i, msg->payload); // global position * 1000
i += put_int32_t_by_index(latitude, i, msg->payload); // global position * 1E7
i += put_int32_t_by_index(longitude, i, msg->payload); // global position * 1E7
i += put_int32_t_by_index(altitude, i, msg->payload); // global position * 1000
return mavlink_finalize_message(msg, system_id, component_id, i);
}
......@@ -54,16 +54,16 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id,
* @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint32_t latitude, uint32_t longitude, uint32_t altitude)
static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint32_t_by_index(latitude, i, msg->payload); // global position * 1E7
i += put_uint32_t_by_index(longitude, i, msg->payload); // global position * 1E7
i += put_uint32_t_by_index(altitude, i, msg->payload); // global position * 1000
i += put_int32_t_by_index(latitude, i, msg->payload); // global position * 1E7
i += put_int32_t_by_index(longitude, i, msg->payload); // global position * 1E7
i += put_int32_t_by_index(altitude, i, msg->payload); // global position * 1000
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
......@@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_encode(uint8_t system_i
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t latitude, uint32_t longitude, uint32_t altitude)
static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
{
mavlink_message_t msg;
mavlink_msg_gps_set_global_origin_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, latitude, longitude, altitude);
......@@ -128,14 +128,14 @@ static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(con
*
* @return global position * 1E7
*/
static inline uint32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg)
static inline int32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
return (uint32_t)r.i;
return (int32_t)r.i;
}
/**
......@@ -143,14 +143,14 @@ static inline uint32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavl
*
* @return global position * 1E7
*/
static inline uint32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg)
static inline int32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[3];
return (uint32_t)r.i;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[3];
return (int32_t)r.i;
}
/**
......@@ -158,14 +158,14 @@ static inline uint32_t mavlink_msg_gps_set_global_origin_get_longitude(const mav
*
* @return global position * 1000
*/
static inline uint32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg)
static inline int32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[3];
return (uint32_t)r.i;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[3];
return (int32_t)r.i;
}
/**
......
......@@ -5,10 +5,10 @@
typedef struct __mavlink_raw_pressure_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float press_abs; ///< Absolute pressure (hectopascal)
float press_diff1; ///< Differential pressure 1 (hectopascal)
float press_diff2; ///< Differential pressure 2 (hectopascal)
int16_t temperature; ///< Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
int16_t press_abs; ///< Absolute pressure (raw)
int16_t press_diff1; ///< Differential pressure 1 (raw)
int16_t press_diff2; ///< Differential pressure 2 (raw)
int16_t temperature; ///< Raw Temperature measurement (raw)
} mavlink_raw_pressure_t;
......@@ -21,22 +21,22 @@ typedef struct __mavlink_raw_pressure_t
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff1 Differential pressure 1 (hectopascal)
* @param press_diff2 Differential pressure 2 (hectopascal)
* @param temperature Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
* @param press_abs Absolute pressure (raw)
* @param press_diff1 Differential pressure 1 (raw)
* @param press_diff2 Differential pressure 2 (raw)
* @param temperature Raw Temperature measurement (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float press_abs, float press_diff1, float press_diff2, int16_t temperature)
static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_float_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_float_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal)
i += put_float_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal)
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (raw)
i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (raw)
i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (raw)
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (raw)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
......@@ -48,22 +48,22 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t
* @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 or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff1 Differential pressure 1 (hectopascal)
* @param press_diff2 Differential pressure 2 (hectopascal)
* @param temperature Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
* @param press_abs Absolute pressure (raw)
* @param press_diff1 Differential pressure 1 (raw)
* @param press_diff2 Differential pressure 2 (raw)
* @param temperature Raw Temperature measurement (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float press_abs, float press_diff1, float press_diff2, int16_t temperature)
static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
i += put_float_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_float_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal)
i += put_float_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal)
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (raw)
i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (raw)
i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (raw)
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (raw)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
......@@ -86,14 +86,14 @@ static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff1 Differential pressure 1 (hectopascal)
* @param press_diff2 Differential pressure 2 (hectopascal)
* @param temperature Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
* @param press_abs Absolute pressure (raw)
* @param press_diff1 Differential pressure 1 (raw)
* @param press_diff2 Differential pressure 2 (raw)
* @param temperature Raw Temperature measurement (raw)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, float press_abs, float press_diff1, float press_diff2, int16_t temperature)
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
mavlink_message_t msg;
mavlink_msg_raw_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff1, press_diff2, temperature);
......@@ -125,58 +125,52 @@ static inline uint64_t mavlink_msg_raw_pressure_get_usec(const mavlink_message_t
/**
* @brief Get field press_abs from raw_pressure message
*
* @return Absolute pressure (hectopascal)
* @return Absolute pressure (raw)
*/
static inline float mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t))[0];
r.b[2] = (msg->payload+sizeof(uint64_t))[1];
r.b[1] = (msg->payload+sizeof(uint64_t))[2];
r.b[0] = (msg->payload+sizeof(uint64_t))[3];
return (float)r.f;
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field press_diff1 from raw_pressure message
*
* @return Differential pressure 1 (hectopascal)
* @return Differential pressure 1 (raw)
*/
static inline float mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3];
return (float)r.f;
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field press_diff2 from raw_pressure message
*
* @return Differential pressure 2 (hectopascal)
* @return Differential pressure 2 (raw)
*/
static inline float mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field temperature from raw_pressure message
*
* @return Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
* @return Raw Temperature measurement (raw)
*/
static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
......
// MESSAGE REQUEST_DYNAMIC_GYRO_CALIBRATION PACKING
#define MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION 67
typedef struct __mavlink_request_dynamic_gyro_calibration_t
{
uint8_t target_system; ///< The system which should auto-calibrate
uint8_t target_component; ///< The system component which should auto-calibrate
float mode; ///< The current ground-truth rpm
uint8_t axis; ///< The axis to calibrate: 0 roll, 1 pitch, 2 yaw
uint16_t time; ///< The time to average over in ms
} mavlink_request_dynamic_gyro_calibration_t;
/**
* @brief Pack a request_dynamic_gyro_calibration message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param mode The current ground-truth rpm
* @param axis The axis to calibrate: 0 roll, 1 pitch, 2 yaw
* @param time The time to average over in ms
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float mode, uint8_t axis, uint16_t time)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION;
i += put_uint8_t_by_index(target_system, i, msg->payload); // The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); // The system component which should auto-calibrate
i += put_float_by_index(mode, i, msg->payload); // The current ground-truth rpm
i += put_uint8_t_by_index(axis, i, msg->payload); // The axis to calibrate: 0 roll, 1 pitch, 2 yaw
i += put_uint16_t_by_index(time, i, msg->payload); // The time to average over in ms
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a request_dynamic_gyro_calibration message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param mode The current ground-truth rpm
* @param axis The axis to calibrate: 0 roll, 1 pitch, 2 yaw
* @param time The time to average over in ms
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float mode, uint8_t axis, uint16_t time)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION;
i += put_uint8_t_by_index(target_system, i, msg->payload); // The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); // The system component which should auto-calibrate
i += put_float_by_index(mode, i, msg->payload); // The current ground-truth rpm
i += put_uint8_t_by_index(axis, i, msg->payload); // The axis to calibrate: 0 roll, 1 pitch, 2 yaw
i += put_uint16_t_by_index(time, i, msg->payload); // The time to average over in ms
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a request_dynamic_gyro_calibration struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param request_dynamic_gyro_calibration C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_dynamic_gyro_calibration_t* request_dynamic_gyro_calibration)
{
return mavlink_msg_request_dynamic_gyro_calibration_pack(system_id, component_id, msg, request_dynamic_gyro_calibration->target_system, request_dynamic_gyro_calibration->target_component, request_dynamic_gyro_calibration->mode, request_dynamic_gyro_calibration->axis, request_dynamic_gyro_calibration->time);
}
/**
* @brief Send a request_dynamic_gyro_calibration message
* @param chan MAVLink channel to send the message
*
* @param target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param mode The current ground-truth rpm
* @param axis The axis to calibrate: 0 roll, 1 pitch, 2 yaw
* @param time The time to average over in ms
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_request_dynamic_gyro_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float mode, uint8_t axis, uint16_t time)
{
mavlink_message_t msg;
mavlink_msg_request_dynamic_gyro_calibration_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, mode, axis, time);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE REQUEST_DYNAMIC_GYRO_CALIBRATION UNPACKING
/**
* @brief Get field target_system from request_dynamic_gyro_calibration message
*
* @return The system which should auto-calibrate
*/
static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_target_system(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field target_component from request_dynamic_gyro_calibration message
*
* @return The system component which should auto-calibrate
*/
static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_target_component(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field mode from request_dynamic_gyro_calibration message
*
* @return The current ground-truth rpm
*/
static inline float mavlink_msg_request_dynamic_gyro_calibration_get_mode(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
return (float)r.f;
}
/**
* @brief Get field axis from request_dynamic_gyro_calibration message
*
* @return The axis to calibrate: 0 roll, 1 pitch, 2 yaw
*/
static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_axis(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
}
/**
* @brief Get field time from request_dynamic_gyro_calibration message
*
* @return The time to average over in ms
*/
static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_get_time(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[1];
return (uint16_t)r.s;
}
/**
* @brief Decode a request_dynamic_gyro_calibration message into a struct
*
* @param msg The message to decode
* @param request_dynamic_gyro_calibration C-struct to decode the message contents into
*/
static inline void mavlink_msg_request_dynamic_gyro_calibration_decode(const mavlink_message_t* msg, mavlink_request_dynamic_gyro_calibration_t* request_dynamic_gyro_calibration)
{
request_dynamic_gyro_calibration->target_system = mavlink_msg_request_dynamic_gyro_calibration_get_target_system(msg);
request_dynamic_gyro_calibration->target_component = mavlink_msg_request_dynamic_gyro_calibration_get_target_component(msg);
request_dynamic_gyro_calibration->mode = mavlink_msg_request_dynamic_gyro_calibration_get_mode(msg);
request_dynamic_gyro_calibration->axis = mavlink_msg_request_dynamic_gyro_calibration_get_axis(msg);
request_dynamic_gyro_calibration->time = mavlink_msg_request_dynamic_gyro_calibration_get_time(msg);
}
// MESSAGE REQUEST_STATIC_CALIBRATION PACKING
#define MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION 68
typedef struct __mavlink_request_static_calibration_t
{
uint8_t target_system; ///< The system which should auto-calibrate
uint8_t target_component; ///< The system component which should auto-calibrate
uint16_t time; ///< The time to average over in ms
} mavlink_request_static_calibration_t;
/**
* @brief Pack a request_static_calibration message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param time The time to average over in ms
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_static_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t time)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION;
i += put_uint8_t_by_index(target_system, i, msg->payload); // The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); // The system component which should auto-calibrate
i += put_uint16_t_by_index(time, i, msg->payload); // The time to average over in ms
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a request_static_calibration message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param time The time to average over in ms
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_static_calibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t time)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION;
i += put_uint8_t_by_index(target_system, i, msg->payload); // The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); // The system component which should auto-calibrate
i += put_uint16_t_by_index(time, i, msg->payload); // The time to average over in ms
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a request_static_calibration struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param request_static_calibration C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_request_static_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_static_calibration_t* request_static_calibration)
{
return mavlink_msg_request_static_calibration_pack(system_id, component_id, msg, request_static_calibration->target_system, request_static_calibration->target_component, request_static_calibration->time);
}
/**
* @brief Send a request_static_calibration message
* @param chan MAVLink channel to send the message
*
* @param target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param time The time to average over in ms
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_request_static_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t time)
{
mavlink_message_t msg;
mavlink_msg_request_static_calibration_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, time);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE REQUEST_STATIC_CALIBRATION UNPACKING
/**
* @brief Get field target_system from request_static_calibration message
*
* @return The system which should auto-calibrate
*/
static inline uint8_t mavlink_msg_request_static_calibration_get_target_system(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field target_component from request_static_calibration message
*
* @return The system component which should auto-calibrate
*/
static inline uint8_t mavlink_msg_request_static_calibration_get_target_component(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field time from request_static_calibration message
*
* @return The time to average over in ms
*/
static inline uint16_t mavlink_msg_request_static_calibration_get_time(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
return (uint16_t)r.s;
}
/**
* @brief Decode a request_static_calibration message into a struct
*
* @param msg The message to decode
* @param request_static_calibration C-struct to decode the message contents into
*/
static inline void mavlink_msg_request_static_calibration_decode(const mavlink_message_t* msg, mavlink_request_static_calibration_t* request_static_calibration)
{
request_static_calibration->target_system = mavlink_msg_request_static_calibration_get_target_system(msg);
request_static_calibration->target_component = mavlink_msg_request_static_calibration_get_target_component(msg);
request_static_calibration->time = mavlink_msg_request_static_calibration_get_time(msg);
}
......@@ -59,6 +59,8 @@ enum MAV_ACTION
MAV_ACTION_CHANGE_MODE = 38,
MAV_ACTION_LOITER_MAX_TURNS = 39,
MAV_ACTION_LOITER_MAX_TIME = 40,
MAV_ACTION_START_HILSIM = 41,
MAV_ACTION_STOP_HILSIM = 42,
MAV_ACTION_NB ///< Number of MAV actions
};
......@@ -85,6 +87,7 @@ enum MAV_STATE
MAV_STATE_ACTIVE,
MAV_STATE_CRITICAL,
MAV_STATE_EMERGENCY,
MAV_STATE_HILSIM,
MAV_STATE_POWEROFF
};
......@@ -139,7 +142,8 @@ enum MAV_FRAME
{
MAV_FRAME_GLOBAL = 0,
MAV_FRAME_LOCAL = 1,
MAV_FRAME_MISSION = 2
MAV_FRAME_MISSION = 2,
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3
};
#define MAVLINK_STX 0x55 ///< Packet start sign
......@@ -178,10 +182,21 @@ typedef enum {
MAVLINK_COMM_0,
MAVLINK_COMM_1,
MAVLINK_COMM_2,
MAVLINK_COMM_3,
MAVLINK_COMM_NB,
MAVLINK_COMM_NB_HIGH = 16
} mavlink_channel_t;
MAVLINK_COMM_3
} mavlink_channel_t;
/*
* applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
* of buffers they will use. If more are used, then the result will be
* a stack overrun
*/
#ifndef MAVLINK_COMM_NUM_BUFFERS
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
# define MAVLINK_COMM_NUM_BUFFERS 16
#else
# define MAVLINK_COMM_NUM_BUFFERS 4
#endif
#endif
typedef enum {
MAVLINK_PARSE_STATE_UNINIT=0,
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Wednesday, March 2 2011, 13:12 UTC
* Generated on Thursday, March 31 2011, 22:06 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
// MESSAGE DEBUG_VECT PACKING
#define MAVLINK_MSG_ID_DEBUG_VECT 90
typedef struct __mavlink_debug_vect_t
{
int8_t name[10]; ///< Name
uint64_t usec; ///< Timestamp
float x; ///< x
float y; ///< y
float z; ///< z
} mavlink_debug_vect_t;
#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
/**
* @brief Send a debug_vect message
*
* @param name Name
* @param usec Timestamp
* @param x x
* @param y y
* @param z z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const int8_t* name, uint64_t usec, float x, float y, float z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
i += put_array_by_index(name, 10, i, msg->payload); //Name
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp
i += put_float_by_index(x, i, msg->payload); //x
i += put_float_by_index(y, i, msg->payload); //y
i += put_float_by_index(z, i, msg->payload); //z
return mavlink_finalize_message(msg, system_id, component_id, i);
}
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 int8_t* name, uint64_t usec, float x, float y, float z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
i += put_array_by_index(name, 10, i, msg->payload); //Name
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp
i += put_float_by_index(x, i, msg->payload); //x
i += put_float_by_index(y, i, msg->payload); //y
i += put_float_by_index(z, i, msg->payload); //z
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
{
return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const int8_t* name, uint64_t usec, float x, float y, float z)
{
mavlink_message_t msg;
mavlink_msg_debug_vect_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, usec, x, y, z);
mavlink_send_uart(chan, &msg);
}
#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, int8_t* r_data)
{
memcpy(r_data, msg->payload, 10);
return 10;
}
/**
* @brief Get field usec from debug_vect message
*
* @return Timestamp
*/
static inline uint64_t mavlink_msg_debug_vect_get_usec(const mavlink_message_t* msg)
{
generic_64bit r;
r.b[7] = (msg->payload+10)[0];
r.b[6] = (msg->payload+10)[1];
r.b[5] = (msg->payload+10)[2];
r.b[4] = (msg->payload+10)[3];
r.b[3] = (msg->payload+10)[4];
r.b[2] = (msg->payload+10)[5];
r.b[1] = (msg->payload+10)[6];
r.b[0] = (msg->payload+10)[7];
return (uint64_t)r.ll;
}
/**
* @brief Get field x from debug_vect message
*
* @return x
*/
static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+10+sizeof(uint64_t))[0];
r.b[2] = (msg->payload+10+sizeof(uint64_t))[1];
r.b[1] = (msg->payload+10+sizeof(uint64_t))[2];
r.b[0] = (msg->payload+10+sizeof(uint64_t))[3];
return (float)r.f;
}
/**
* @brief Get field y from debug_vect message
*
* @return y
*/
static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[0];
r.b[2] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[1];
r.b[1] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[2];
r.b[0] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field z from debug_vect message
*
* @return z
*/
static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
{
mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
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);
}
// MESSAGE ENCAPSULATED_IMAGE PACKING
#define MAVLINK_MSG_ID_ENCAPSULATED_IMAGE 171
typedef struct __mavlink_encapsulated_image_t
{
uint8_t seqnr; ///< sequence number (starting with 0 on every transmission)
uint8_t data[254]; ///< image data bytes
} mavlink_encapsulated_image_t;
#define MAVLINK_MSG_ENCAPSULATED_IMAGE_FIELD_DATA_LEN 254
/**
* @brief Send a encapsulated_image message
*
* @param seqnr sequence number (starting with 0 on every transmission)
* @param data image data bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_encapsulated_image_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t seqnr, const uint8_t* data)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_IMAGE;
i += put_uint8_t_by_index(seqnr, i, msg->payload); //sequence number (starting with 0 on every transmission)
i += put_array_by_index((int8_t*)data, sizeof(uint8_t)*254, i, msg->payload); //image data bytes
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_encapsulated_image_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_image_t* encapsulated_image)
{
return mavlink_msg_encapsulated_image_pack(system_id, component_id, msg, encapsulated_image->seqnr, encapsulated_image->data);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_encapsulated_image_send(mavlink_channel_t chan, uint8_t seqnr, const uint8_t* data)
{
mavlink_message_t msg;
mavlink_msg_encapsulated_image_pack(mavlink_system.sysid, mavlink_system.compid, &msg, seqnr, data);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE ENCAPSULATED_IMAGE UNPACKING
/**
* @brief Get field seqnr from encapsulated_image message
*
* @return sequence number (starting with 0 on every transmission)
*/
static inline uint8_t mavlink_msg_encapsulated_image_get_seqnr(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field data from encapsulated_image message
*
* @return image data bytes
*/
static inline uint16_t mavlink_msg_encapsulated_image_get_data(const mavlink_message_t* msg, uint8_t* r_data)
{
memcpy(r_data, msg->payload+sizeof(uint8_t), sizeof(uint8_t)*254);
return sizeof(uint8_t)*254;
}
static inline void mavlink_msg_encapsulated_image_decode(const mavlink_message_t* msg, mavlink_encapsulated_image_t* encapsulated_image)
{
encapsulated_image->seqnr = mavlink_msg_encapsulated_image_get_seqnr(msg);
mavlink_msg_encapsulated_image_get_data(msg, encapsulated_image->data);
}
// MESSAGE GET_IMAGE_ACK PACKING
#define MAVLINK_MSG_ID_GET_IMAGE_ACK 170
typedef struct __mavlink_get_image_ack_t
{
uint16_t size; ///< image size in bytes (65000 byte max)
uint8_t packets; ///< number of packets beeing sent
uint8_t payload; ///< image payload size (normally 254 byte)
uint8_t quality; ///< JPEG quality out of [0,100]
} mavlink_get_image_ack_t;
/**
* @brief Send a get_image_ack message
*
* @param size image size in bytes (65000 byte max)
* @param packets number of packets beeing sent
* @param payload image payload size (normally 254 byte)
* @param quality JPEG quality out of [0,100]
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_get_image_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t size, uint8_t packets, uint8_t payload, uint8_t quality)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GET_IMAGE_ACK;
i += put_uint16_t_by_index(size, i, msg->payload); //image size in bytes (65000 byte max)
i += put_uint8_t_by_index(packets, i, msg->payload); //number of packets beeing sent
i += put_uint8_t_by_index(payload, i, msg->payload); //image payload size (normally 254 byte)
i += put_uint8_t_by_index(quality, i, msg->payload); //JPEG quality out of [0,100]
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_get_image_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_get_image_ack_t* get_image_ack)
{
return mavlink_msg_get_image_ack_pack(system_id, component_id, msg, get_image_ack->size, get_image_ack->packets, get_image_ack->payload, get_image_ack->quality);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_get_image_ack_send(mavlink_channel_t chan, uint16_t size, uint8_t packets, uint8_t payload, uint8_t quality)
{
mavlink_message_t msg;
mavlink_msg_get_image_ack_pack(mavlink_system.sysid, mavlink_system.compid, &msg, size, packets, payload, quality);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE GET_IMAGE_ACK UNPACKING
/**
* @brief Get field size from get_image_ack message
*
* @return image size in bytes (65000 byte max)
*/
static inline uint16_t mavlink_msg_get_image_ack_get_size(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload)[0];
r.b[0] = (msg->payload)[1];
return (uint16_t)r.s;
}
/**
* @brief Get field packets from get_image_ack message
*
* @return number of packets beeing sent
*/
static inline uint8_t mavlink_msg_get_image_ack_get_packets(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint16_t))[0];
}
/**
* @brief Get field payload from get_image_ack message
*
* @return image payload size (normally 254 byte)
*/
static inline uint8_t mavlink_msg_get_image_ack_get_payload(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field quality from get_image_ack message
*
* @return JPEG quality out of [0,100]
*/
static inline uint8_t mavlink_msg_get_image_ack_get_quality(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
static inline void mavlink_msg_get_image_ack_decode(const mavlink_message_t* msg, mavlink_get_image_ack_t* get_image_ack)
{
get_image_ack->size = mavlink_msg_get_image_ack_get_size(msg);
get_image_ack->packets = mavlink_msg_get_image_ack_get_packets(msg);
get_image_ack->payload = mavlink_msg_get_image_ack_get_payload(msg);
get_image_ack->quality = mavlink_msg_get_image_ack_get_quality(msg);
}
// MESSAGE MANUAL_CONTROL PACKING
#define MAVLINK_MSG_ID_MANUAL_CONTROL 84
typedef struct __mavlink_manual_control_t
{
uint8_t target; ///< The system to be controlled
float roll; ///< roll
float pitch; ///< pitch
float yaw; ///< yaw
float thrust; ///< thrust
uint8_t roll_manual; ///< roll control enabled auto:0, manual:1
uint8_t pitch_manual; ///< pitch auto:0, manual:1
uint8_t yaw_manual; ///< yaw auto:0, manual:1
uint8_t thrust_manual; ///< thrust auto:0, manual:1
} mavlink_manual_control_t;
/**
* @brief Send a manual_control message
*
* @param target The system to be controlled
* @param roll roll
* @param pitch pitch
* @param yaw yaw
* @param thrust thrust
* @param roll_manual roll control enabled auto:0, manual:1
* @param pitch_manual pitch auto:0, manual:1
* @param yaw_manual yaw auto:0, manual:1
* @param thrust_manual thrust auto:0, manual:1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
i += put_uint8_t_by_index(target, i, msg->payload); //The system to be controlled
i += put_float_by_index(roll, i, msg->payload); //roll
i += put_float_by_index(pitch, i, msg->payload); //pitch
i += put_float_by_index(yaw, i, msg->payload); //yaw
i += put_float_by_index(thrust, i, msg->payload); //thrust
i += put_uint8_t_by_index(roll_manual, i, msg->payload); //roll control enabled auto:0, manual:1
i += put_uint8_t_by_index(pitch_manual, i, msg->payload); //pitch auto:0, manual:1
i += put_uint8_t_by_index(yaw_manual, i, msg->payload); //yaw auto:0, manual:1
i += put_uint8_t_by_index(thrust_manual, i, msg->payload); //thrust auto:0, manual:1
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control)
{
return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->roll, manual_control->pitch, manual_control->yaw, manual_control->thrust, manual_control->roll_manual, manual_control->pitch_manual, manual_control->yaw_manual, manual_control->thrust_manual);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
{
mavlink_message_t msg;
mavlink_msg_manual_control_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE MANUAL_CONTROL UNPACKING
/**
* @brief Get field target from manual_control message
*
* @return The system to be controlled
*/
static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field roll from manual_control message
*
* @return roll
*/
static inline float mavlink_msg_manual_control_get_roll(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t))[3];
return (float)r.f;
}
/**
* @brief Get field pitch from manual_control message
*
* @return pitch
*/
static inline float mavlink_msg_manual_control_get_pitch(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field yaw from manual_control message
*
* @return yaw
*/
static inline float mavlink_msg_manual_control_get_yaw(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field thrust from manual_control message
*
* @return thrust
*/
static inline float mavlink_msg_manual_control_get_thrust(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field roll_manual from manual_control message
*
* @return roll control enabled auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_roll_manual(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
}
/**
* @brief Get field pitch_manual from manual_control message
*
* @return pitch auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_pitch_manual(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
}
/**
* @brief Get field yaw_manual from manual_control message
*
* @return yaw auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_yaw_manual(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field thrust_manual from manual_control message
*
* @return thrust auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_thrust_manual(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control)
{
manual_control->target = mavlink_msg_manual_control_get_target(msg);
manual_control->roll = mavlink_msg_manual_control_get_roll(msg);
manual_control->pitch = mavlink_msg_manual_control_get_pitch(msg);
manual_control->yaw = mavlink_msg_manual_control_get_yaw(msg);
manual_control->thrust = mavlink_msg_manual_control_get_thrust(msg);
manual_control->roll_manual = mavlink_msg_manual_control_get_roll_manual(msg);
manual_control->pitch_manual = mavlink_msg_manual_control_get_pitch_manual(msg);
manual_control->yaw_manual = mavlink_msg_manual_control_get_yaw_manual(msg);
manual_control->thrust_manual = mavlink_msg_manual_control_get_thrust_manual(msg);
}
// MESSAGE REQUEST_DATA_STREAM PACKING
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 81
typedef struct __mavlink_request_data_stream_t
{
uint8_t target_system; ///< The target requested to send the message stream.
uint8_t target_component; ///< The target requested to send the message stream.
uint8_t req_stream_id; ///< The ID of the requested message type
uint16_t req_message_rate; ///< The requested interval between two messages of this type
uint8_t start_stop; ///< 1 to start sending, 0 to stop sending.
} mavlink_request_data_stream_t;
/**
* @brief Send a request_data_stream message
*
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
* @param req_stream_id The ID of the requested message type
* @param req_message_rate The requested interval between two messages of this type
* @param start_stop 1 to start sending, 0 to stop sending.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
i += put_uint8_t_by_index(target_system, i, msg->payload); //The target requested to send the message stream.
i += put_uint8_t_by_index(target_component, i, msg->payload); //The target requested to send the message stream.
i += put_uint8_t_by_index(req_stream_id, i, msg->payload); //The ID of the requested message type
i += put_uint16_t_by_index(req_message_rate, i, msg->payload); //The requested interval between two messages of this type
i += put_uint8_t_by_index(start_stop, i, msg->payload); //1 to start sending, 0 to stop sending.
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream)
{
return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
{
mavlink_message_t msg;
mavlink_msg_request_data_stream_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, req_stream_id, req_message_rate, start_stop);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE REQUEST_DATA_STREAM UNPACKING
/**
* @brief Get field target_system from request_data_stream message
*
* @return The target requested to send the message stream.
*/
static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field target_component from request_data_stream message
*
* @return The target requested to send the message stream.
*/
static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field req_stream_id from request_data_stream message
*
* @return The ID of the requested message type
*/
static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field req_message_rate from request_data_stream message
*
* @return The requested interval between two messages of this type
*/
static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
return (uint16_t)r.s;
}
/**
* @brief Get field start_stop from request_data_stream message
*
* @return 1 to start sending, 0 to stop sending.
*/
static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
}
static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream)
{
request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg);
request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg);
request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg);
request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg);
request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg);
}
// MESSAGE REQUEST_DYNAMIC_GYRO_CALIBRATION PACKING
#define MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION 82
typedef struct __mavlink_request_dynamic_gyro_calibration_t
{
uint8_t target_system; ///< The system which should auto-calibrate
uint8_t target_component; ///< The system component which should auto-calibrate
float mode; ///< The current ground-truth rpm
uint8_t axis; ///< The axis to calibrate: 0 roll, 1 pitch, 2 yaw
uint16_t time; ///< The time to average over in ms
} mavlink_request_dynamic_gyro_calibration_t;
/**
* @brief Send a request_dynamic_gyro_calibration message
*
* @param target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param mode The current ground-truth rpm
* @param axis The axis to calibrate: 0 roll, 1 pitch, 2 yaw
* @param time The time to average over in ms
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float mode, uint8_t axis, uint16_t time)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION;
i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate
i += put_float_by_index(mode, i, msg->payload); //The current ground-truth rpm
i += put_uint8_t_by_index(axis, i, msg->payload); //The axis to calibrate: 0 roll, 1 pitch, 2 yaw
i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_dynamic_gyro_calibration_t* request_dynamic_gyro_calibration)
{
return mavlink_msg_request_dynamic_gyro_calibration_pack(system_id, component_id, msg, request_dynamic_gyro_calibration->target_system, request_dynamic_gyro_calibration->target_component, request_dynamic_gyro_calibration->mode, request_dynamic_gyro_calibration->axis, request_dynamic_gyro_calibration->time);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_request_dynamic_gyro_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float mode, uint8_t axis, uint16_t time)
{
mavlink_message_t msg;
mavlink_msg_request_dynamic_gyro_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, mode, axis, time);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE REQUEST_DYNAMIC_GYRO_CALIBRATION UNPACKING
/**
* @brief Get field target_system from request_dynamic_gyro_calibration message
*
* @return The system which should auto-calibrate
*/
static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_target_system(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field target_component from request_dynamic_gyro_calibration message
*
* @return The system component which should auto-calibrate
*/
static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_target_component(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field mode from request_dynamic_gyro_calibration message
*
* @return The current ground-truth rpm
*/
static inline float mavlink_msg_request_dynamic_gyro_calibration_get_mode(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
return (float)r.f;
}
/**
* @brief Get field axis from request_dynamic_gyro_calibration message
*
* @return The axis to calibrate: 0 roll, 1 pitch, 2 yaw
*/
static inline uint8_t mavlink_msg_request_dynamic_gyro_calibration_get_axis(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0];
}
/**
* @brief Get field time from request_dynamic_gyro_calibration message
*
* @return The time to average over in ms
*/
static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_get_time(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t))[1];
return (uint16_t)r.s;
}
static inline void mavlink_msg_request_dynamic_gyro_calibration_decode(const mavlink_message_t* msg, mavlink_request_dynamic_gyro_calibration_t* request_dynamic_gyro_calibration)
{
request_dynamic_gyro_calibration->target_system = mavlink_msg_request_dynamic_gyro_calibration_get_target_system(msg);
request_dynamic_gyro_calibration->target_component = mavlink_msg_request_dynamic_gyro_calibration_get_target_component(msg);
request_dynamic_gyro_calibration->mode = mavlink_msg_request_dynamic_gyro_calibration_get_mode(msg);
request_dynamic_gyro_calibration->axis = mavlink_msg_request_dynamic_gyro_calibration_get_axis(msg);
request_dynamic_gyro_calibration->time = mavlink_msg_request_dynamic_gyro_calibration_get_time(msg);
}
// MESSAGE REQUEST_STATIC_CALIBRATION PACKING
#define MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION 83
typedef struct __mavlink_request_static_calibration_t
{
uint8_t target_system; ///< The system which should auto-calibrate
uint8_t target_component; ///< The system component which should auto-calibrate
uint16_t time; ///< The time to average over in ms
} mavlink_request_static_calibration_t;
/**
* @brief Send a request_static_calibration message
*
* @param target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param time The time to average over in ms
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_static_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t time)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION;
i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate
i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_request_static_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_static_calibration_t* request_static_calibration)
{
return mavlink_msg_request_static_calibration_pack(system_id, component_id, msg, request_static_calibration->target_system, request_static_calibration->target_component, request_static_calibration->time);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_request_static_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t time)
{
mavlink_message_t msg;
mavlink_msg_request_static_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target_system, target_component, time);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE REQUEST_STATIC_CALIBRATION UNPACKING
/**
* @brief Get field target_system from request_static_calibration message
*
* @return The system which should auto-calibrate
*/
static inline uint8_t mavlink_msg_request_static_calibration_get_target_system(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field target_component from request_static_calibration message
*
* @return The system component which should auto-calibrate
*/
static inline uint8_t mavlink_msg_request_static_calibration_get_target_component(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field time from request_static_calibration message
*
* @return The time to average over in ms
*/
static inline uint16_t mavlink_msg_request_static_calibration_get_time(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
return (uint16_t)r.s;
}
static inline void mavlink_msg_request_static_calibration_decode(const mavlink_message_t* msg, mavlink_request_static_calibration_t* request_static_calibration)
{
request_static_calibration->target_system = mavlink_msg_request_static_calibration_get_target_system(msg);
request_static_calibration->target_component = mavlink_msg_request_static_calibration_get_target_component(msg);
request_static_calibration->time = mavlink_msg_request_static_calibration_get_time(msg);
}
// MESSAGE SET_ALTITUDE PACKING
#define MAVLINK_MSG_ID_SET_ALTITUDE 80
typedef struct __mavlink_set_altitude_t
{
uint8_t target; ///< The system setting the altitude
uint32_t mode; ///< The new altitude in meters
} mavlink_set_altitude_t;
/**
* @brief Send a set_altitude message
*
* @param target The system setting the altitude
* @param mode The new altitude in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint32_t mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the altitude
i += put_uint32_t_by_index(mode, i, msg->payload); //The new altitude in meters
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_set_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_altitude_t* set_altitude)
{
return mavlink_msg_set_altitude_pack(system_id, component_id, msg, set_altitude->target, set_altitude->mode);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_set_altitude_send(mavlink_channel_t chan, uint8_t target, uint32_t mode)
{
mavlink_message_t msg;
mavlink_msg_set_altitude_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, mode);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SET_ALTITUDE UNPACKING
/**
* @brief Get field target from set_altitude message
*
* @return The system setting the altitude
*/
static inline uint8_t mavlink_msg_set_altitude_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field mode from set_altitude message
*
* @return The new altitude in meters
*/
static inline uint32_t mavlink_msg_set_altitude_get_mode(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t))[3];
return (uint32_t)r.i;
}
static inline void mavlink_msg_set_altitude_decode(const mavlink_message_t* msg, mavlink_set_altitude_t* set_altitude)
{
set_altitude->target = mavlink_msg_set_altitude_get_target(msg);
set_altitude->mode = mavlink_msg_set_altitude_get_mode(msg);
}
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Wednesday, March 2 2011, 13:12 UTC
* Generated on Thursday, March 31 2011, 22:06 UTC
*/
#ifndef PIXHAWK_H
#define PIXHAWK_H
......
......@@ -34,12 +34,7 @@ static void mavlink_parse_state_initialize(mavlink_status_t* initStatus)
static inline mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
{
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH];
#else
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB];
#endif
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
return &m_mavlink_status[chan];
}
......@@ -73,7 +68,7 @@ static inline uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t
msg->compid = component_id;
// One sequence number per component
msg->seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq;
mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq+1;
mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq+1;
checksum = crc_calculate((uint8_t*)((void*)msg), length + MAVLINK_CORE_HEADER_LEN);
msg->ck_a = (uint8_t)(checksum & 0xFF); ///< High byte
msg->ck_b = (uint8_t)(checksum >> 8); ///< Low byte
......@@ -202,11 +197,8 @@ static inline void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
*/
static inline uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
{
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB_HIGH];
#else
static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB];
#endif
static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS];
// Initializes only once, values keep unchanged after first initialization
mavlink_parse_state_initialize(mavlink_get_channel_status(chan));
......@@ -391,23 +383,13 @@ static inline uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messag
/*
static inline uint8_t mavlink_parse_char_new(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
{
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH];
static uint8_t m_msgbuf[MAVLINK_COMM_NB_HIGH][MAVLINK_MAX_PACKET_LEN * 2];
static uint8_t m_msgbuf_index[MAVLINK_COMM_NB_HIGH];
static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB_HIGH];
static uint8_t m_packet_start[MAVLINK_COMM_NB_HIGH][MAVLINK_PACKET_START_CANDIDATES];
static uint8_t m_packet_start_index_read[MAVLINK_COMM_NB_HIGH];
static uint8_t m_packet_start_index_write[MAVLINK_COMM_NB_HIGH];
#else
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB];
static uint8_t m_msgbuf[MAVLINK_COMM_NB][MAVLINK_MAX_PACKET_LEN * 2];
static uint8_t m_msgbuf_index[MAVLINK_COMM_NB];
static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB];
static uint8_t m_packet_start[MAVLINK_COMM_NB][MAVLINK_PACKET_START_CANDIDATES];
static uint8_t m_packet_start_index_read[MAVLINK_COMM_NB];
static uint8_t m_packet_start_index_write[MAVLINK_COMM_NB];
#endif
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
static uint8_t m_msgbuf[MAVLINK_COMM_NUM_BUFFERS][MAVLINK_MAX_PACKET_LEN * 2];
static uint8_t m_msgbuf_index[MAVLINK_COMM_NUM_BUFFERS];
static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS];
static uint8_t m_packet_start[MAVLINK_COMM_NUM_BUFFERS][MAVLINK_PACKET_START_CANDIDATES];
static uint8_t m_packet_start_index_read[MAVLINK_COMM_NUM_BUFFERS];
static uint8_t m_packet_start_index_write[MAVLINK_COMM_NUM_BUFFERS];
// Set a packet start candidate index if sign is start sign
if (c == MAVLINK_STX)
......@@ -417,13 +399,8 @@ static inline uint8_t mavlink_parse_char_new(uint8_t chan, uint8_t c, mavlink_me
// Parse normally, if a CRC mismatch occurs retry with the next packet index
}
//#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
// static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH];
// static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB_HIGH];
//#else
// static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB];
// static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB];
//#endif
// static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
// static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS];
//// Initializes only once, values keep unchanged after first initialization
// mavlink_parse_state_initialize(&m_mavlink_status[chan]);
//
......@@ -575,6 +552,7 @@ typedef union __generic_64bit
{
uint8_t b[8];
int64_t ll; ///< Long long (64 bit)
double d; ///< IEEE-754 double precision floating point
} generic_64bit;
/**
......@@ -883,6 +861,103 @@ void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
}
*/
static inline void mavlink_send_uart_uint8_t(mavlink_channel_t chan, uint8_t b, uint16_t* checksum)
{
crc_accumulate(b, checksum);
comm_send_ch(chan, b);
}
static inline void mavlink_send_uart_int8_t(mavlink_channel_t chan, int8_t b, uint16_t* checksum)
{
crc_accumulate(b, checksum);
comm_send_ch(chan, b);
}
static inline void mavlink_send_uart_uint16_t(mavlink_channel_t chan, uint16_t b, uint16_t* checksum)
{
char s;
s = (b>>8)&0xff;
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
s = (b & 0xff);
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
}
static inline void mavlink_send_uart_int16_t(mavlink_channel_t chan, int16_t b, uint16_t* checksum)
{
mavlink_send_uart_uint16_t(chan, b, checksum);
}
static inline void mavlink_send_uart_uint32_t(mavlink_channel_t chan, uint32_t b, uint16_t* checksum)
{
char s;
s = (b>>24)&0xff;
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
s = (b>>16)&0xff;
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
s = (b>>8)&0xff;
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
s = (b & 0xff);
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
}
static inline void mavlink_send_uart_int32_t(mavlink_channel_t chan, int32_t b, uint16_t* checksum)
{
mavlink_send_uart_uint32_t(chan, b, checksum);
}
static inline void mavlink_send_uart_uint64_t(mavlink_channel_t chan, uint64_t b, uint16_t* checksum)
{
char s;
s = (b>>56)&0xff;
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
s = (b>>48)&0xff;
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
s = (b>>40)&0xff;
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
s = (b>>32)&0xff;
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
s = (b>>24)&0xff;
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
s = (b>>16)&0xff;
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
s = (b>>8)&0xff;
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
s = (b & 0xff);
comm_send_ch(chan, s);
crc_accumulate(s, checksum);
}
static inline void mavlink_send_uart_int64_t(mavlink_channel_t chan, int64_t b, uint16_t* checksum)
{
mavlink_send_uart_uint64_t(chan, b, checksum);
}
static inline void mavlink_send_uart_float(mavlink_channel_t chan, float b, uint16_t* checksum)
{
generic_32bit g;
g.f = b;
mavlink_send_uart_uint32_t(chan, g.i, checksum);
}
static inline void mavlink_send_uart_double(mavlink_channel_t chan, double b, uint16_t* checksum)
{
generic_64bit g;
g.d = b;
mavlink_send_uart_uint32_t(chan, g.ll, checksum);
}
static inline void mavlink_send_uart(mavlink_channel_t chan, mavlink_message_t* msg)
{
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Thursday, December 2 2010, 10:44 UTC
* Generated on Thursday, March 31 2011, 22:06 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
......@@ -13,7 +13,10 @@ typedef struct __mavlink_air_data_t
/**
* @brief Send a air_data message
* @brief Pack a air_data message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param dynamicPressure Dynamic pressure (Pa)
* @param staticPressure Static pressure (Pa)
......@@ -25,37 +28,63 @@ static inline uint16_t mavlink_msg_air_data_pack(uint8_t system_id, uint8_t comp
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_AIR_DATA;
i += put_float_by_index(dynamicPressure, i, msg->payload); //Dynamic pressure (Pa)
i += put_float_by_index(staticPressure, i, msg->payload); //Static pressure (Pa)
i += put_uint16_t_by_index(temperature, i, msg->payload); //Board temperature
i += put_float_by_index(dynamicPressure, i, msg->payload); // Dynamic pressure (Pa)
i += put_float_by_index(staticPressure, i, msg->payload); // Static pressure (Pa)
i += put_uint16_t_by_index(temperature, i, msg->payload); // Board temperature
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_air_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float dynamicPressure, float staticPressure, uint16_t temperature)
/**
* @brief Pack a air_data message
* @param system_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 dynamicPressure Dynamic pressure (Pa)
* @param staticPressure Static pressure (Pa)
* @param temperature Board temperature
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_air_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float dynamicPressure, float staticPressure, uint16_t temperature)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_AIR_DATA;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the air data
i += put_float_by_index(dynamicPressure, i, msg->payload); //Dynamic pressure (Pa)
i += put_float_by_index(staticPressure, i, msg->payload); //Static pressure (Pa)
i += put_uint16_t_by_index(temperature, i, msg->payload); //Board temperature
i += put_float_by_index(dynamicPressure, i, msg->payload); // Dynamic pressure (Pa)
i += put_float_by_index(staticPressure, i, msg->payload); // Static pressure (Pa)
i += put_uint16_t_by_index(temperature, i, msg->payload); // Board temperature
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a air_data struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param air_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_air_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_air_data_t* air_data)
{
return mavlink_msg_air_data_pack(system_id, component_id, msg, air_data->dynamicPressure, air_data->staticPressure, air_data->temperature);
}
/**
* @brief Send a air_data message
* @param chan MAVLink channel to send the message
*
* @param dynamicPressure Dynamic pressure (Pa)
* @param staticPressure Static pressure (Pa)
* @param temperature Board temperature
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_air_data_send(mavlink_channel_t chan, float dynamicPressure, float staticPressure, uint16_t temperature)
{
mavlink_message_t msg;
mavlink_msg_air_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, dynamicPressure, staticPressure, temperature);
mavlink_msg_air_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, dynamicPressure, staticPressure, temperature);
mavlink_send_uart(chan, &msg);
}
......@@ -105,6 +134,12 @@ static inline uint16_t mavlink_msg_air_data_get_temperature(const mavlink_messag
return (uint16_t)r.s;
}
/**
* @brief Decode a air_data message into a struct
*
* @param msg The message to decode
* @param air_data C-struct to decode the message contents into
*/
static inline void mavlink_msg_air_data_decode(const mavlink_message_t* msg, mavlink_air_data_t* air_data)
{
air_data->dynamicPressure = mavlink_msg_air_data_get_dynamicPressure(msg);
......
......@@ -13,7 +13,10 @@ typedef struct __mavlink_cpu_load_t
/**
* @brief Send a cpu_load message
* @brief Pack a cpu_load message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param sensLoad Sensor DSC Load
* @param ctrlLoad Control DSC Load
......@@ -25,37 +28,63 @@ static inline uint16_t mavlink_msg_cpu_load_pack(uint8_t system_id, uint8_t comp
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CPU_LOAD;
i += put_uint8_t_by_index(sensLoad, i, msg->payload); //Sensor DSC Load
i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); //Control DSC Load
i += put_uint16_t_by_index(batVolt, i, msg->payload); //Battery Voltage in millivolts
i += put_uint8_t_by_index(sensLoad, i, msg->payload); // Sensor DSC Load
i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); // Control DSC Load
i += put_uint16_t_by_index(batVolt, i, msg->payload); // Battery Voltage in millivolts
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_cpu_load_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
/**
* @brief Pack a cpu_load message
* @param system_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 sensLoad Sensor DSC Load
* @param ctrlLoad Control DSC Load
* @param batVolt Battery Voltage in millivolts
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cpu_load_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CPU_LOAD;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the CPU load
i += put_uint8_t_by_index(sensLoad, i, msg->payload); //Sensor DSC Load
i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); //Control DSC Load
i += put_uint16_t_by_index(batVolt, i, msg->payload); //Battery Voltage in millivolts
i += put_uint8_t_by_index(sensLoad, i, msg->payload); // Sensor DSC Load
i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); // Control DSC Load
i += put_uint16_t_by_index(batVolt, i, msg->payload); // Battery Voltage in millivolts
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a cpu_load struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param cpu_load C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cpu_load_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cpu_load_t* cpu_load)
{
return mavlink_msg_cpu_load_pack(system_id, component_id, msg, cpu_load->sensLoad, cpu_load->ctrlLoad, cpu_load->batVolt);
}
/**
* @brief Send a cpu_load message
* @param chan MAVLink channel to send the message
*
* @param sensLoad Sensor DSC Load
* @param ctrlLoad Control DSC Load
* @param batVolt Battery Voltage in millivolts
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_cpu_load_send(mavlink_channel_t chan, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt)
{
mavlink_message_t msg;
mavlink_msg_cpu_load_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, sensLoad, ctrlLoad, batVolt);
mavlink_msg_cpu_load_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, sensLoad, ctrlLoad, batVolt);
mavlink_send_uart(chan, &msg);
}
......@@ -95,6 +124,12 @@ static inline uint16_t mavlink_msg_cpu_load_get_batVolt(const mavlink_message_t*
return (uint16_t)r.s;
}
/**
* @brief Decode a cpu_load message into a struct
*
* @param msg The message to decode
* @param cpu_load C-struct to decode the message contents into
*/
static inline void mavlink_msg_cpu_load_decode(const mavlink_message_t* msg, mavlink_cpu_load_t* cpu_load)
{
cpu_load->sensLoad = mavlink_msg_cpu_load_get_sensLoad(msg);
......
......@@ -12,7 +12,10 @@ typedef struct __mavlink_ctrl_srfc_pt_t
/**
* @brief Send a ctrl_srfc_pt message
* @brief Pack a ctrl_srfc_pt message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target The system setting the commands
* @param bitfieldPt Bitfield containing the PT configuration
......@@ -23,23 +26,59 @@ static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack(uint8_t system_id, uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CTRL_SRFC_PT;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the commands
i += put_uint16_t_by_index(bitfieldPt, i, msg->payload); //Bitfield containing the PT configuration
i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands
i += put_uint16_t_by_index(bitfieldPt, i, msg->payload); // Bitfield containing the PT configuration
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a ctrl_srfc_pt message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target The system setting the commands
* @param bitfieldPt Bitfield containing the PT configuration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint16_t bitfieldPt)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CTRL_SRFC_PT;
i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands
i += put_uint16_t_by_index(bitfieldPt, i, msg->payload); // Bitfield containing the PT configuration
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a ctrl_srfc_pt struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param ctrl_srfc_pt C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ctrl_srfc_pt_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ctrl_srfc_pt_t* ctrl_srfc_pt)
{
return mavlink_msg_ctrl_srfc_pt_pack(system_id, component_id, msg, ctrl_srfc_pt->target, ctrl_srfc_pt->bitfieldPt);
}
/**
* @brief Send a ctrl_srfc_pt message
* @param chan MAVLink channel to send the message
*
* @param target The system setting the commands
* @param bitfieldPt Bitfield containing the PT configuration
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ctrl_srfc_pt_send(mavlink_channel_t chan, uint8_t target, uint16_t bitfieldPt)
{
mavlink_message_t msg;
mavlink_msg_ctrl_srfc_pt_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, bitfieldPt);
mavlink_msg_ctrl_srfc_pt_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, bitfieldPt);
mavlink_send_uart(chan, &msg);
}
......@@ -69,6 +108,12 @@ static inline uint16_t mavlink_msg_ctrl_srfc_pt_get_bitfieldPt(const mavlink_mes
return (uint16_t)r.s;
}
/**
* @brief Decode a ctrl_srfc_pt message into a struct
*
* @param msg The message to decode
* @param ctrl_srfc_pt C-struct to decode the message contents into
*/
static inline void mavlink_msg_ctrl_srfc_pt_decode(const mavlink_message_t* msg, mavlink_ctrl_srfc_pt_t* ctrl_srfc_pt)
{
ctrl_srfc_pt->target = mavlink_msg_ctrl_srfc_pt_get_target(msg);
......
......@@ -16,7 +16,10 @@ typedef struct __mavlink_data_log_t
/**
* @brief Send a data_log message
* @brief Pack a data_log message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param fl_1 Log value 1
* @param fl_2 Log value 2
......@@ -31,27 +34,75 @@ static inline uint16_t mavlink_msg_data_log_pack(uint8_t system_id, uint8_t comp
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DATA_LOG;
i += put_float_by_index(fl_1, i, msg->payload); //Log value 1
i += put_float_by_index(fl_2, i, msg->payload); //Log value 2
i += put_float_by_index(fl_3, i, msg->payload); //Log value 3
i += put_float_by_index(fl_4, i, msg->payload); //Log value 4
i += put_float_by_index(fl_5, i, msg->payload); //Log value 5
i += put_float_by_index(fl_6, i, msg->payload); //Log value 6
i += put_float_by_index(fl_1, i, msg->payload); // Log value 1
i += put_float_by_index(fl_2, i, msg->payload); // Log value 2
i += put_float_by_index(fl_3, i, msg->payload); // Log value 3
i += put_float_by_index(fl_4, i, msg->payload); // Log value 4
i += put_float_by_index(fl_5, i, msg->payload); // Log value 5
i += put_float_by_index(fl_6, i, msg->payload); // Log value 6
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a data_log message
* @param system_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 fl_1 Log value 1
* @param fl_2 Log value 2
* @param fl_3 Log value 3
* @param fl_4 Log value 4
* @param fl_5 Log value 5
* @param fl_6 Log value 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_log_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DATA_LOG;
i += put_float_by_index(fl_1, i, msg->payload); // Log value 1
i += put_float_by_index(fl_2, i, msg->payload); // Log value 2
i += put_float_by_index(fl_3, i, msg->payload); // Log value 3
i += put_float_by_index(fl_4, i, msg->payload); // Log value 4
i += put_float_by_index(fl_5, i, msg->payload); // Log value 5
i += put_float_by_index(fl_6, i, msg->payload); // Log value 6
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a data_log struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param data_log C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data_log_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_log_t* data_log)
{
return mavlink_msg_data_log_pack(system_id, component_id, msg, data_log->fl_1, data_log->fl_2, data_log->fl_3, data_log->fl_4, data_log->fl_5, data_log->fl_6);
}
/**
* @brief Send a data_log message
* @param chan MAVLink channel to send the message
*
* @param fl_1 Log value 1
* @param fl_2 Log value 2
* @param fl_3 Log value 3
* @param fl_4 Log value 4
* @param fl_5 Log value 5
* @param fl_6 Log value 6
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_data_log_send(mavlink_channel_t chan, float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6)
{
mavlink_message_t msg;
mavlink_msg_data_log_pack(mavlink_system.sysid, mavlink_system.compid, &msg, fl_1, fl_2, fl_3, fl_4, fl_5, fl_6);
mavlink_msg_data_log_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, fl_1, fl_2, fl_3, fl_4, fl_5, fl_6);
mavlink_send_uart(chan, &msg);
}
......@@ -148,6 +199,12 @@ static inline float mavlink_msg_data_log_get_fl_6(const mavlink_message_t* msg)
return (float)r.f;
}
/**
* @brief Decode a data_log message into a struct
*
* @param msg The message to decode
* @param data_log C-struct to decode the message contents into
*/
static inline void mavlink_msg_data_log_decode(const mavlink_message_t* msg, mavlink_data_log_t* data_log)
{
data_log->fl_1 = mavlink_msg_data_log_get_fl_1(msg);
......
......@@ -16,7 +16,10 @@ typedef struct __mavlink_diagnostic_t
/**
* @brief Send a diagnostic message
* @brief Pack a diagnostic message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param diagFl1 Diagnostic float 1
* @param diagFl2 Diagnostic float 2
......@@ -31,43 +34,75 @@ static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t co
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC;
i += put_float_by_index(diagFl1, i, msg->payload); //Diagnostic float 1
i += put_float_by_index(diagFl2, i, msg->payload); //Diagnostic float 2
i += put_float_by_index(diagFl3, i, msg->payload); //Diagnostic float 3
i += put_int16_t_by_index(diagSh1, i, msg->payload); //Diagnostic short 1
i += put_int16_t_by_index(diagSh2, i, msg->payload); //Diagnostic short 2
i += put_int16_t_by_index(diagSh3, i, msg->payload); //Diagnostic short 3
i += put_float_by_index(diagFl1, i, msg->payload); // Diagnostic float 1
i += put_float_by_index(diagFl2, i, msg->payload); // Diagnostic float 2
i += put_float_by_index(diagFl3, i, msg->payload); // Diagnostic float 3
i += put_int16_t_by_index(diagSh1, i, msg->payload); // Diagnostic short 1
i += put_int16_t_by_index(diagSh2, i, msg->payload); // Diagnostic short 2
i += put_int16_t_by_index(diagSh3, i, msg->payload); // Diagnostic short 3
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
/**
* @brief Pack a diagnostic message
* @param system_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 diagFl1 Diagnostic float 1
* @param diagFl2 Diagnostic float 2
* @param diagFl3 Diagnostic float 3
* @param diagSh1 Diagnostic short 1
* @param diagSh2 Diagnostic short 2
* @param diagSh3 Diagnostic short 3
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic
i += put_float_by_index(diagFl1, i, msg->payload); //Diagnostic float 1
i += put_float_by_index(diagFl2, i, msg->payload); //Diagnostic float 2
i += put_float_by_index(diagFl3, i, msg->payload); //Diagnostic float 3
i += put_int16_t_by_index(diagSh1, i, msg->payload); //Diagnostic short 1
i += put_int16_t_by_index(diagSh2, i, msg->payload); //Diagnostic short 2
i += put_int16_t_by_index(diagSh3, i, msg->payload); //Diagnostic short 3
i += put_float_by_index(diagFl1, i, msg->payload); // Diagnostic float 1
i += put_float_by_index(diagFl2, i, msg->payload); // Diagnostic float 2
i += put_float_by_index(diagFl3, i, msg->payload); // Diagnostic float 3
i += put_int16_t_by_index(diagSh1, i, msg->payload); // Diagnostic short 1
i += put_int16_t_by_index(diagSh2, i, msg->payload); // Diagnostic short 2
i += put_int16_t_by_index(diagSh3, i, msg->payload); // Diagnostic short 3
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a diagnostic struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param diagnostic C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_diagnostic_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_diagnostic_t* diagnostic)
{
return mavlink_msg_diagnostic_pack(system_id, component_id, msg, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3);
}
/**
* @brief Send a diagnostic message
* @param chan MAVLink channel to send the message
*
* @param diagFl1 Diagnostic float 1
* @param diagFl2 Diagnostic float 2
* @param diagFl3 Diagnostic float 3
* @param diagSh1 Diagnostic short 1
* @param diagSh2 Diagnostic short 2
* @param diagSh3 Diagnostic short 3
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_diagnostic_send(mavlink_channel_t chan, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3)
{
mavlink_message_t msg;
mavlink_msg_diagnostic_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3);
mavlink_msg_diagnostic_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3);
mavlink_send_uart(chan, &msg);
}
......@@ -158,6 +193,12 @@ static inline int16_t mavlink_msg_diagnostic_get_diagSh3(const mavlink_message_t
return (int16_t)r.s;
}
/**
* @brief Decode a diagnostic message into a struct
*
* @param msg The message to decode
* @param diagnostic C-struct to decode the message contents into
*/
static inline void mavlink_msg_diagnostic_decode(const mavlink_message_t* msg, mavlink_diagnostic_t* diagnostic)
{
diagnostic->diagFl1 = mavlink_msg_diagnostic_get_diagFl1(msg);
......
// MESSAGE FILTERED_DATA PACKING
#define MAVLINK_MSG_ID_FILTERED_DATA 178
typedef struct __mavlink_filtered_data_t
{
float aX; ///< Accelerometer X value (m/s^2)
float aY; ///< Accelerometer Y value (m/s^2)
float aZ; ///< Accelerometer Z value (m/s^2)
float gX; ///< Gyro X value (rad/s)
float gY; ///< Gyro Y value (rad/s)
float gZ; ///< Gyro Z value (rad/s)
float mX; ///< Magnetometer X (normalized to 1)
float mY; ///< Magnetometer Y (normalized to 1)
float mZ; ///< Magnetometer Z (normalized to 1)
} mavlink_filtered_data_t;
/**
* @brief Send a filtered_data message
*
* @param aX Accelerometer X value (m/s^2)
* @param aY Accelerometer Y value (m/s^2)
* @param aZ Accelerometer Z value (m/s^2)
* @param gX Gyro X value (rad/s)
* @param gY Gyro Y value (rad/s)
* @param gZ Gyro Z value (rad/s)
* @param mX Magnetometer X (normalized to 1)
* @param mY Magnetometer Y (normalized to 1)
* @param mZ Magnetometer Z (normalized to 1)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_filtered_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float aX, float aY, float aZ, float gX, float gY, float gZ, float mX, float mY, float mZ)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_FILTERED_DATA;
i += put_float_by_index(aX, i, msg->payload); //Accelerometer X value (m/s^2)
i += put_float_by_index(aY, i, msg->payload); //Accelerometer Y value (m/s^2)
i += put_float_by_index(aZ, i, msg->payload); //Accelerometer Z value (m/s^2)
i += put_float_by_index(gX, i, msg->payload); //Gyro X value (rad/s)
i += put_float_by_index(gY, i, msg->payload); //Gyro Y value (rad/s)
i += put_float_by_index(gZ, i, msg->payload); //Gyro Z value (rad/s)
i += put_float_by_index(mX, i, msg->payload); //Magnetometer X (normalized to 1)
i += put_float_by_index(mY, i, msg->payload); //Magnetometer Y (normalized to 1)
i += put_float_by_index(mZ, i, msg->payload); //Magnetometer Z (normalized to 1)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_filtered_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_filtered_data_t* filtered_data)
{
return mavlink_msg_filtered_data_pack(system_id, component_id, msg, filtered_data->aX, filtered_data->aY, filtered_data->aZ, filtered_data->gX, filtered_data->gY, filtered_data->gZ, filtered_data->mX, filtered_data->mY, filtered_data->mZ);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_filtered_data_send(mavlink_channel_t chan, float aX, float aY, float aZ, float gX, float gY, float gZ, float mX, float mY, float mZ)
{
mavlink_message_t msg;
mavlink_msg_filtered_data_pack(mavlink_system.sysid, mavlink_system.compid, &msg, aX, aY, aZ, gX, gY, gZ, mX, mY, mZ);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE FILTERED_DATA UNPACKING
/**
* @brief Get field aX from filtered_data message
*
* @return Accelerometer X value (m/s^2)
*/
static inline float mavlink_msg_filtered_data_get_aX(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
/**
* @brief Get field aY from filtered_data message
*
* @return Accelerometer Y value (m/s^2)
*/
static inline float mavlink_msg_filtered_data_get_aY(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field aZ from filtered_data message
*
* @return Accelerometer Z value (m/s^2)
*/
static inline float mavlink_msg_filtered_data_get_aZ(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field gX from filtered_data message
*
* @return Gyro X value (rad/s)
*/
static inline float mavlink_msg_filtered_data_get_gX(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field gY from filtered_data message
*
* @return Gyro Y value (rad/s)
*/
static inline float mavlink_msg_filtered_data_get_gY(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field gZ from filtered_data message
*
* @return Gyro Z value (rad/s)
*/
static inline float mavlink_msg_filtered_data_get_gZ(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field mX from filtered_data message
*
* @return Magnetometer X (normalized to 1)
*/
static inline float mavlink_msg_filtered_data_get_mX(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field mY from filtered_data message
*
* @return Magnetometer Y (normalized to 1)
*/
static inline float mavlink_msg_filtered_data_get_mY(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field mZ from filtered_data message
*
* @return Magnetometer Z (normalized to 1)
*/
static inline float mavlink_msg_filtered_data_get_mZ(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
static inline void mavlink_msg_filtered_data_decode(const mavlink_message_t* msg, mavlink_filtered_data_t* filtered_data)
{
filtered_data->aX = mavlink_msg_filtered_data_get_aX(msg);
filtered_data->aY = mavlink_msg_filtered_data_get_aY(msg);
filtered_data->aZ = mavlink_msg_filtered_data_get_aZ(msg);
filtered_data->gX = mavlink_msg_filtered_data_get_gX(msg);
filtered_data->gY = mavlink_msg_filtered_data_get_gY(msg);
filtered_data->gZ = mavlink_msg_filtered_data_get_gZ(msg);
filtered_data->mX = mavlink_msg_filtered_data_get_mX(msg);
filtered_data->mY = mavlink_msg_filtered_data_get_mY(msg);
filtered_data->mZ = mavlink_msg_filtered_data_get_mZ(msg);
}
......@@ -17,7 +17,10 @@ typedef struct __mavlink_gps_date_time_t
/**
* @brief Send a gps_date_time message
* @brief Pack a gps_date_time message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param year Year reported by Gps
* @param month Month reported by Gps
......@@ -33,28 +36,79 @@ static inline uint16_t mavlink_msg_gps_date_time_pack(uint8_t system_id, uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME;
i += put_uint8_t_by_index(year, i, msg->payload); //Year reported by Gps
i += put_uint8_t_by_index(month, i, msg->payload); //Month reported by Gps
i += put_uint8_t_by_index(day, i, msg->payload); //Day reported by Gps
i += put_uint8_t_by_index(hour, i, msg->payload); //Hour reported by Gps
i += put_uint8_t_by_index(min, i, msg->payload); //Min reported by Gps
i += put_uint8_t_by_index(sec, i, msg->payload); //Sec reported by Gps
i += put_uint8_t_by_index(visSat, i, msg->payload); //Visible sattelites reported by Gps
i += put_uint8_t_by_index(year, i, msg->payload); // Year reported by Gps
i += put_uint8_t_by_index(month, i, msg->payload); // Month reported by Gps
i += put_uint8_t_by_index(day, i, msg->payload); // Day reported by Gps
i += put_uint8_t_by_index(hour, i, msg->payload); // Hour reported by Gps
i += put_uint8_t_by_index(min, i, msg->payload); // Min reported by Gps
i += put_uint8_t_by_index(sec, i, msg->payload); // Sec reported by Gps
i += put_uint8_t_by_index(visSat, i, msg->payload); // Visible sattelites reported by Gps
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a gps_date_time message
* @param system_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 year Year reported by Gps
* @param month Month reported by Gps
* @param day Day reported by Gps
* @param hour Hour reported by Gps
* @param min Min reported by Gps
* @param sec Sec reported by Gps
* @param visSat Visible sattelites reported by Gps
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_date_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME;
i += put_uint8_t_by_index(year, i, msg->payload); // Year reported by Gps
i += put_uint8_t_by_index(month, i, msg->payload); // Month reported by Gps
i += put_uint8_t_by_index(day, i, msg->payload); // Day reported by Gps
i += put_uint8_t_by_index(hour, i, msg->payload); // Hour reported by Gps
i += put_uint8_t_by_index(min, i, msg->payload); // Min reported by Gps
i += put_uint8_t_by_index(sec, i, msg->payload); // Sec reported by Gps
i += put_uint8_t_by_index(visSat, i, msg->payload); // Visible sattelites reported by Gps
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a gps_date_time struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_date_time C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_date_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_date_time_t* gps_date_time)
{
return mavlink_msg_gps_date_time_pack(system_id, component_id, msg, gps_date_time->year, gps_date_time->month, gps_date_time->day, gps_date_time->hour, gps_date_time->min, gps_date_time->sec, gps_date_time->visSat);
}
/**
* @brief Send a gps_date_time message
* @param chan MAVLink channel to send the message
*
* @param year Year reported by Gps
* @param month Month reported by Gps
* @param day Day reported by Gps
* @param hour Hour reported by Gps
* @param min Min reported by Gps
* @param sec Sec reported by Gps
* @param visSat Visible sattelites reported by Gps
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_date_time_send(mavlink_channel_t chan, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
{
mavlink_message_t msg;
mavlink_msg_gps_date_time_pack(mavlink_system.sysid, mavlink_system.compid, &msg, year, month, day, hour, min, sec, visSat);
mavlink_msg_gps_date_time_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, year, month, day, hour, min, sec, visSat);
mavlink_send_uart(chan, &msg);
}
......@@ -131,6 +185,12 @@ static inline uint8_t mavlink_msg_gps_date_time_get_visSat(const mavlink_message
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a gps_date_time message into a struct
*
* @param msg The message to decode
* @param gps_date_time C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_date_time_decode(const mavlink_message_t* msg, mavlink_gps_date_time_t* gps_date_time)
{
gps_date_time->year = mavlink_msg_gps_date_time_get_year(msg);
......
......@@ -14,7 +14,10 @@ typedef struct __mavlink_mid_lvl_cmds_t
/**
* @brief Send a mid_lvl_cmds message
* @brief Pack a mid_lvl_cmds message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target The system setting the commands
* @param hCommand Commanded Airspeed
......@@ -27,25 +30,67 @@ static inline uint16_t mavlink_msg_mid_lvl_cmds_pack(uint8_t system_id, uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the commands
i += put_float_by_index(hCommand, i, msg->payload); //Commanded Airspeed
i += put_float_by_index(uCommand, i, msg->payload); //Log value 2
i += put_float_by_index(rCommand, i, msg->payload); //Log value 3
i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands
i += put_float_by_index(hCommand, i, msg->payload); // Commanded Airspeed
i += put_float_by_index(uCommand, i, msg->payload); // Log value 2
i += put_float_by_index(rCommand, i, msg->payload); // Log value 3
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a mid_lvl_cmds message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target The system setting the commands
* @param hCommand Commanded Airspeed
* @param uCommand Log value 2
* @param rCommand Log value 3
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mid_lvl_cmds_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float hCommand, float uCommand, float rCommand)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS;
i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands
i += put_float_by_index(hCommand, i, msg->payload); // Commanded Airspeed
i += put_float_by_index(uCommand, i, msg->payload); // Log value 2
i += put_float_by_index(rCommand, i, msg->payload); // Log value 3
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a mid_lvl_cmds struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mid_lvl_cmds C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mid_lvl_cmds_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mid_lvl_cmds_t* mid_lvl_cmds)
{
return mavlink_msg_mid_lvl_cmds_pack(system_id, component_id, msg, mid_lvl_cmds->target, mid_lvl_cmds->hCommand, mid_lvl_cmds->uCommand, mid_lvl_cmds->rCommand);
}
/**
* @brief Send a mid_lvl_cmds message
* @param chan MAVLink channel to send the message
*
* @param target The system setting the commands
* @param hCommand Commanded Airspeed
* @param uCommand Log value 2
* @param rCommand Log value 3
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mid_lvl_cmds_send(mavlink_channel_t chan, uint8_t target, float hCommand, float uCommand, float rCommand)
{
mavlink_message_t msg;
mavlink_msg_mid_lvl_cmds_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, hCommand, uCommand, rCommand);
mavlink_msg_mid_lvl_cmds_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, hCommand, uCommand, rCommand);
mavlink_send_uart(chan, &msg);
}
......@@ -107,6 +152,12 @@ static inline float mavlink_msg_mid_lvl_cmds_get_rCommand(const mavlink_message_
return (float)r.f;
}
/**
* @brief Decode a mid_lvl_cmds message into a struct
*
* @param msg The message to decode
* @param mid_lvl_cmds C-struct to decode the message contents into
*/
static inline void mavlink_msg_mid_lvl_cmds_decode(const mavlink_message_t* msg, mavlink_mid_lvl_cmds_t* mid_lvl_cmds)
{
mid_lvl_cmds->target = mavlink_msg_mid_lvl_cmds_get_target(msg);
......
// MESSAGE PID PACKING
#define MAVLINK_MSG_ID_PID 182
typedef struct __mavlink_pid_t
{
uint8_t target; ///< The system setting the PID values
float pVal; ///< Proportional gain
float iVal; ///< Integral gain
float dVal; ///< Derivative gain
uint8_t idx; ///< PID loop index
} mavlink_pid_t;
/**
* @brief Send a pid message
*
* @param target The system setting the PID values
* @param pVal Proportional gain
* @param iVal Integral gain
* @param dVal Derivative gain
* @param idx PID loop index
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pid_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float pVal, float iVal, float dVal, uint8_t idx)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PID;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the PID values
i += put_float_by_index(pVal, i, msg->payload); //Proportional gain
i += put_float_by_index(iVal, i, msg->payload); //Integral gain
i += put_float_by_index(dVal, i, msg->payload); //Derivative gain
i += put_uint8_t_by_index(idx, i, msg->payload); //PID loop index
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_pid_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pid_t* pid)
{
return mavlink_msg_pid_pack(system_id, component_id, msg, pid->target, pid->pVal, pid->iVal, pid->dVal, pid->idx);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_pid_send(mavlink_channel_t chan, uint8_t target, float pVal, float iVal, float dVal, uint8_t idx)
{
mavlink_message_t msg;
mavlink_msg_pid_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, pVal, iVal, dVal, idx);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE PID UNPACKING
/**
* @brief Get field target from pid message
*
* @return The system setting the PID values
*/
static inline uint8_t mavlink_msg_pid_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field pVal from pid message
*
* @return Proportional gain
*/
static inline float mavlink_msg_pid_get_pVal(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t))[3];
return (float)r.f;
}
/**
* @brief Get field iVal from pid message
*
* @return Integral gain
*/
static inline float mavlink_msg_pid_get_iVal(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field dVal from pid message
*
* @return Derivative gain
*/
static inline float mavlink_msg_pid_get_dVal(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field idx from pid message
*
* @return PID loop index
*/
static inline uint8_t mavlink_msg_pid_get_idx(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
}
static inline void mavlink_msg_pid_decode(const mavlink_message_t* msg, mavlink_pid_t* pid)
{
pid->target = mavlink_msg_pid_get_target(msg);
pid->pVal = mavlink_msg_pid_get_pVal(msg);
pid->iVal = mavlink_msg_pid_get_iVal(msg);
pid->dVal = mavlink_msg_pid_get_dVal(msg);
pid->idx = mavlink_msg_pid_get_idx(msg);
}
// MESSAGE PILOT_CONSOLE PACKING
#define MAVLINK_MSG_ID_PILOT_CONSOLE 174
typedef struct __mavlink_pilot_console_t
{
uint16_t dt; ///< Pilot's console throttle command
uint16_t dla; ///< Pilot's console left aileron command
uint16_t dra; ///< Pilot's console right aileron command
uint16_t dr; ///< Pilot's console rudder command
uint16_t de; ///< Pilot's console elevator command
} mavlink_pilot_console_t;
/**
* @brief Send a pilot_console message
*
* @param dt Pilot's console throttle command
* @param dla Pilot's console left aileron command
* @param dra Pilot's console right aileron command
* @param dr Pilot's console rudder command
* @param de Pilot's console elevator command
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pilot_console_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t dt, uint16_t dla, uint16_t dra, uint16_t dr, uint16_t de)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PILOT_CONSOLE;
i += put_uint16_t_by_index(dt, i, msg->payload); //Pilot's console throttle command
i += put_uint16_t_by_index(dla, i, msg->payload); //Pilot's console left aileron command
i += put_uint16_t_by_index(dra, i, msg->payload); //Pilot's console right aileron command
i += put_uint16_t_by_index(dr, i, msg->payload); //Pilot's console rudder command
i += put_uint16_t_by_index(de, i, msg->payload); //Pilot's console elevator command
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_pilot_console_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint16_t dt, uint16_t dla, uint16_t dra, uint16_t dr, uint16_t de)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PILOT_CONSOLE;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic
i += put_uint16_t_by_index(dt, i, msg->payload); //Pilot's console throttle command
i += put_uint16_t_by_index(dla, i, msg->payload); //Pilot's console left aileron command
i += put_uint16_t_by_index(dra, i, msg->payload); //Pilot's console right aileron command
i += put_uint16_t_by_index(dr, i, msg->payload); //Pilot's console rudder command
i += put_uint16_t_by_index(de, i, msg->payload); //Pilot's console elevator command
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
static inline uint16_t mavlink_msg_pilot_console_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pilot_console_t* pilot_console)
{
return mavlink_msg_pilot_console_pack(system_id, component_id, msg, pilot_console->dt, pilot_console->dla, pilot_console->dra, pilot_console->dr, pilot_console->de);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_pilot_console_send(mavlink_channel_t chan, uint16_t dt, uint16_t dla, uint16_t dra, uint16_t dr, uint16_t de)
{
mavlink_message_t msg;
mavlink_msg_pilot_console_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, dt, dla, dra, dr, de);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE PILOT_CONSOLE UNPACKING
/**
* @brief Get field dt from pilot_console message
*
* @return Pilot's console throttle command
*/
static inline uint16_t mavlink_msg_pilot_console_get_dt(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload)[0];
r.b[0] = (msg->payload)[1];
return (uint16_t)r.s;
}
/**
* @brief Get field dla from pilot_console message
*
* @return Pilot's console left aileron command
*/
static inline uint16_t mavlink_msg_pilot_console_get_dla(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
/**
* @brief Get field dra from pilot_console message
*
* @return Pilot's console right aileron command
*/
static inline uint16_t mavlink_msg_pilot_console_get_dra(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
/**
* @brief Get field dr from pilot_console message
*
* @return Pilot's console rudder command
*/
static inline uint16_t mavlink_msg_pilot_console_get_dr(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
/**
* @brief Get field de from pilot_console message
*
* @return Pilot's console elevator command
*/
static inline uint16_t mavlink_msg_pilot_console_get_de(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
return (uint16_t)r.s;
}
static inline void mavlink_msg_pilot_console_decode(const mavlink_message_t* msg, mavlink_pilot_console_t* pilot_console)
{
pilot_console->dt = mavlink_msg_pilot_console_get_dt(msg);
pilot_console->dla = mavlink_msg_pilot_console_get_dla(msg);
pilot_console->dra = mavlink_msg_pilot_console_get_dra(msg);
pilot_console->dr = mavlink_msg_pilot_console_get_dr(msg);
pilot_console->de = mavlink_msg_pilot_console_get_de(msg);
}
......@@ -16,7 +16,10 @@ typedef struct __mavlink_sensor_bias_t
/**
* @brief Send a sensor_bias message
* @brief Pack a sensor_bias message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param axBias Accelerometer X bias (m/s)
* @param ayBias Accelerometer Y bias (m/s)
......@@ -31,43 +34,75 @@ static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t c
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
i += put_float_by_index(axBias, i, msg->payload); //Accelerometer X bias (m/s)
i += put_float_by_index(ayBias, i, msg->payload); //Accelerometer Y bias (m/s)
i += put_float_by_index(azBias, i, msg->payload); //Accelerometer Z bias (m/s)
i += put_float_by_index(gxBias, i, msg->payload); //Gyro X bias (rad/s)
i += put_float_by_index(gyBias, i, msg->payload); //Gyro Y bias (rad/s)
i += put_float_by_index(gzBias, i, msg->payload); //Gyro Z bias (rad/s)
i += put_float_by_index(axBias, i, msg->payload); // Accelerometer X bias (m/s)
i += put_float_by_index(ayBias, i, msg->payload); // Accelerometer Y bias (m/s)
i += put_float_by_index(azBias, i, msg->payload); // Accelerometer Z bias (m/s)
i += put_float_by_index(gxBias, i, msg->payload); // Gyro X bias (rad/s)
i += put_float_by_index(gyBias, i, msg->payload); // Gyro Y bias (rad/s)
i += put_float_by_index(gzBias, i, msg->payload); // Gyro Z bias (rad/s)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
/**
* @brief Pack a sensor_bias message
* @param system_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 axBias Accelerometer X bias (m/s)
* @param ayBias Accelerometer Y bias (m/s)
* @param azBias Accelerometer Z bias (m/s)
* @param gxBias Gyro X bias (rad/s)
* @param gyBias Gyro Y bias (rad/s)
* @param gzBias Gyro Z bias (rad/s)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the biases
i += put_float_by_index(axBias, i, msg->payload); //Accelerometer X bias (m/s)
i += put_float_by_index(ayBias, i, msg->payload); //Accelerometer Y bias (m/s)
i += put_float_by_index(azBias, i, msg->payload); //Accelerometer Z bias (m/s)
i += put_float_by_index(gxBias, i, msg->payload); //Gyro X bias (rad/s)
i += put_float_by_index(gyBias, i, msg->payload); //Gyro Y bias (rad/s)
i += put_float_by_index(gzBias, i, msg->payload); //Gyro Z bias (rad/s)
i += put_float_by_index(axBias, i, msg->payload); // Accelerometer X bias (m/s)
i += put_float_by_index(ayBias, i, msg->payload); // Accelerometer Y bias (m/s)
i += put_float_by_index(azBias, i, msg->payload); // Accelerometer Z bias (m/s)
i += put_float_by_index(gxBias, i, msg->payload); // Gyro X bias (rad/s)
i += put_float_by_index(gyBias, i, msg->payload); // Gyro Y bias (rad/s)
i += put_float_by_index(gzBias, i, msg->payload); // Gyro Z bias (rad/s)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a sensor_bias struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sensor_bias C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensor_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_bias_t* sensor_bias)
{
return mavlink_msg_sensor_bias_pack(system_id, component_id, msg, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias);
}
/**
* @brief Send a sensor_bias message
* @param chan MAVLink channel to send the message
*
* @param axBias Accelerometer X bias (m/s)
* @param ayBias Accelerometer Y bias (m/s)
* @param azBias Accelerometer Z bias (m/s)
* @param gxBias Gyro X bias (rad/s)
* @param gyBias Gyro Y bias (rad/s)
* @param gzBias Gyro Z bias (rad/s)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
{
mavlink_message_t msg;
mavlink_msg_sensor_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, axBias, ayBias, azBias, gxBias, gyBias, gzBias);
mavlink_msg_sensor_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, axBias, ayBias, azBias, gxBias, gyBias, gzBias);
mavlink_send_uart(chan, &msg);
}
......@@ -164,6 +199,12 @@ static inline float mavlink_msg_sensor_bias_get_gzBias(const mavlink_message_t*
return (float)r.f;
}
/**
* @brief Decode a sensor_bias message into a struct
*
* @param msg The message to decode
* @param sensor_bias C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensor_bias_decode(const mavlink_message_t* msg, mavlink_sensor_bias_t* sensor_bias)
{
sensor_bias->axBias = mavlink_msg_sensor_bias_get_axBias(msg);
......
......@@ -13,7 +13,10 @@ typedef struct __mavlink_slugs_action_t
/**
* @brief Send a slugs_action message
* @brief Pack a slugs_action message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target The system reporting the action
* @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
......@@ -25,24 +28,63 @@ static inline uint16_t mavlink_msg_slugs_action_pack(uint8_t system_id, uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SLUGS_ACTION;
i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the action
i += put_uint8_t_by_index(actionId, i, msg->payload); //Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
i += put_uint16_t_by_index(actionVal, i, msg->payload); //Value associated with the action
i += put_uint8_t_by_index(target, i, msg->payload); // The system reporting the action
i += put_uint8_t_by_index(actionId, i, msg->payload); // Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
i += put_uint16_t_by_index(actionVal, i, msg->payload); // Value associated with the action
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a slugs_action message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target The system reporting the action
* @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
* @param actionVal Value associated with the action
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_slugs_action_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t actionId, uint16_t actionVal)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SLUGS_ACTION;
i += put_uint8_t_by_index(target, i, msg->payload); // The system reporting the action
i += put_uint8_t_by_index(actionId, i, msg->payload); // Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
i += put_uint16_t_by_index(actionVal, i, msg->payload); // Value associated with the action
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a slugs_action struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param slugs_action C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_slugs_action_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_slugs_action_t* slugs_action)
{
return mavlink_msg_slugs_action_pack(system_id, component_id, msg, slugs_action->target, slugs_action->actionId, slugs_action->actionVal);
}
/**
* @brief Send a slugs_action message
* @param chan MAVLink channel to send the message
*
* @param target The system reporting the action
* @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names
* @param actionVal Value associated with the action
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_slugs_action_send(mavlink_channel_t chan, uint8_t target, uint8_t actionId, uint16_t actionVal)
{
mavlink_message_t msg;
mavlink_msg_slugs_action_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, actionId, actionVal);
mavlink_msg_slugs_action_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, actionId, actionVal);
mavlink_send_uart(chan, &msg);
}
......@@ -82,6 +124,12 @@ static inline uint16_t mavlink_msg_slugs_action_get_actionVal(const mavlink_mess
return (uint16_t)r.s;
}
/**
* @brief Decode a slugs_action message into a struct
*
* @param msg The message to decode
* @param slugs_action C-struct to decode the message contents into
*/
static inline void mavlink_msg_slugs_action_decode(const mavlink_message_t* msg, mavlink_slugs_action_t* slugs_action)
{
slugs_action->target = mavlink_msg_slugs_action_get_target(msg);
......
......@@ -19,7 +19,10 @@ typedef struct __mavlink_slugs_navigation_t
/**
* @brief Send a slugs_navigation message
* @brief Pack a slugs_navigation message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param u_m Measured Airspeed prior to the Nav Filter
* @param phi_c Commanded Roll
......@@ -37,30 +40,87 @@ static inline uint16_t mavlink_msg_slugs_navigation_pack(uint8_t system_id, uint
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SLUGS_NAVIGATION;
i += put_float_by_index(u_m, i, msg->payload); //Measured Airspeed prior to the Nav Filter
i += put_float_by_index(phi_c, i, msg->payload); //Commanded Roll
i += put_float_by_index(theta_c, i, msg->payload); //Commanded Pitch
i += put_float_by_index(psiDot_c, i, msg->payload); //Commanded Turn rate
i += put_float_by_index(ay_body, i, msg->payload); //Y component of the body acceleration
i += put_float_by_index(totalDist, i, msg->payload); //Total Distance to Run on this leg of Navigation
i += put_float_by_index(dist2Go, i, msg->payload); //Remaining distance to Run on this leg of Navigation
i += put_uint8_t_by_index(fromWP, i, msg->payload); //Origin WP
i += put_uint8_t_by_index(toWP, i, msg->payload); //Destination WP
i += put_float_by_index(u_m, i, msg->payload); // Measured Airspeed prior to the Nav Filter
i += put_float_by_index(phi_c, i, msg->payload); // Commanded Roll
i += put_float_by_index(theta_c, i, msg->payload); // Commanded Pitch
i += put_float_by_index(psiDot_c, i, msg->payload); // Commanded Turn rate
i += put_float_by_index(ay_body, i, msg->payload); // Y component of the body acceleration
i += put_float_by_index(totalDist, i, msg->payload); // Total Distance to Run on this leg of Navigation
i += put_float_by_index(dist2Go, i, msg->payload); // Remaining distance to Run on this leg of Navigation
i += put_uint8_t_by_index(fromWP, i, msg->payload); // Origin WP
i += put_uint8_t_by_index(toWP, i, msg->payload); // Destination WP
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a slugs_navigation message
* @param system_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 u_m Measured Airspeed prior to the Nav Filter
* @param phi_c Commanded Roll
* @param theta_c Commanded Pitch
* @param psiDot_c Commanded Turn rate
* @param ay_body Y component of the body acceleration
* @param totalDist Total Distance to Run on this leg of Navigation
* @param dist2Go Remaining distance to Run on this leg of Navigation
* @param fromWP Origin WP
* @param toWP Destination WP
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_slugs_navigation_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float u_m, float phi_c, float theta_c, float psiDot_c, float ay_body, float totalDist, float dist2Go, uint8_t fromWP, uint8_t toWP)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SLUGS_NAVIGATION;
i += put_float_by_index(u_m, i, msg->payload); // Measured Airspeed prior to the Nav Filter
i += put_float_by_index(phi_c, i, msg->payload); // Commanded Roll
i += put_float_by_index(theta_c, i, msg->payload); // Commanded Pitch
i += put_float_by_index(psiDot_c, i, msg->payload); // Commanded Turn rate
i += put_float_by_index(ay_body, i, msg->payload); // Y component of the body acceleration
i += put_float_by_index(totalDist, i, msg->payload); // Total Distance to Run on this leg of Navigation
i += put_float_by_index(dist2Go, i, msg->payload); // Remaining distance to Run on this leg of Navigation
i += put_uint8_t_by_index(fromWP, i, msg->payload); // Origin WP
i += put_uint8_t_by_index(toWP, i, msg->payload); // Destination WP
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a slugs_navigation struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param slugs_navigation C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_slugs_navigation_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_slugs_navigation_t* slugs_navigation)
{
return mavlink_msg_slugs_navigation_pack(system_id, component_id, msg, slugs_navigation->u_m, slugs_navigation->phi_c, slugs_navigation->theta_c, slugs_navigation->psiDot_c, slugs_navigation->ay_body, slugs_navigation->totalDist, slugs_navigation->dist2Go, slugs_navigation->fromWP, slugs_navigation->toWP);
}
/**
* @brief Send a slugs_navigation message
* @param chan MAVLink channel to send the message
*
* @param u_m Measured Airspeed prior to the Nav Filter
* @param phi_c Commanded Roll
* @param theta_c Commanded Pitch
* @param psiDot_c Commanded Turn rate
* @param ay_body Y component of the body acceleration
* @param totalDist Total Distance to Run on this leg of Navigation
* @param dist2Go Remaining distance to Run on this leg of Navigation
* @param fromWP Origin WP
* @param toWP Destination WP
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_slugs_navigation_send(mavlink_channel_t chan, float u_m, float phi_c, float theta_c, float psiDot_c, float ay_body, float totalDist, float dist2Go, uint8_t fromWP, uint8_t toWP)
{
mavlink_message_t msg;
mavlink_msg_slugs_navigation_pack(mavlink_system.sysid, mavlink_system.compid, &msg, u_m, phi_c, theta_c, psiDot_c, ay_body, totalDist, dist2Go, fromWP, toWP);
mavlink_msg_slugs_navigation_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, u_m, phi_c, theta_c, psiDot_c, ay_body, totalDist, dist2Go, fromWP, toWP);
mavlink_send_uart(chan, &msg);
}
......@@ -192,6 +252,12 @@ static inline uint8_t mavlink_msg_slugs_navigation_get_toWP(const mavlink_messag
return (uint8_t)(msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a slugs_navigation message into a struct
*
* @param msg The message to decode
* @param slugs_navigation C-struct to decode the message contents into
*/
static inline void mavlink_msg_slugs_navigation_decode(const mavlink_message_t* msg, mavlink_slugs_navigation_t* slugs_navigation)
{
slugs_navigation->u_m = mavlink_msg_slugs_navigation_get_u_m(msg);
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Thursday, December 2 2010, 10:44 UTC
* Generated on Thursday, March 31 2011, 22:06 UTC
*/
#ifndef SLUGS_H
#define SLUGS_H
......@@ -17,6 +17,17 @@ extern "C" {
#include "../common/common.h"
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
// ENUM DEFINITIONS
......@@ -26,15 +37,11 @@ extern "C" {
#include "./mavlink_msg_air_data.h"
#include "./mavlink_msg_sensor_bias.h"
#include "./mavlink_msg_diagnostic.h"
#include "./mavlink_msg_pilot_console.h"
#include "./mavlink_msg_pwm_commands.h"
#include "./mavlink_msg_slugs_navigation.h"
#include "./mavlink_msg_data_log.h"
#include "./mavlink_msg_filtered_data.h"
#include "./mavlink_msg_gps_date_time.h"
#include "./mavlink_msg_mid_lvl_cmds.h"
#include "./mavlink_msg_ctrl_srfc_pt.h"
#include "./mavlink_msg_pid.h"
#include "./mavlink_msg_slugs_action.h"
#ifdef __cplusplus
}
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, February 15 2011, 15:58 UTC
* Generated on Thursday, March 31 2011, 22:06 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
// MESSAGE REQUEST_RADIO_CALIBRATION PACKING
#define MAVLINK_MSG_ID_REQUEST_RADIO_CALIBRATION 83
typedef struct __mavlink_request_radio_calibration_t
{
uint8_t unused; ///< Unused field. Included to prevent compile time warnings
} mavlink_request_radio_calibration_t;
/**
* @brief Send a request_radio_calibration message
*
* @param unused Unused field. Included to prevent compile time warnings
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_radio_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t unused)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_RADIO_CALIBRATION;
i += put_uint8_t_by_index(unused, i, msg->payload); //Unused field. Included to prevent compile time warnings
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_request_radio_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_radio_calibration_t* request_radio_calibration)
{
return mavlink_msg_request_radio_calibration_pack(system_id, component_id, msg, request_radio_calibration->unused);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_request_radio_calibration_send(mavlink_channel_t chan, uint8_t unused)
{
mavlink_message_t msg;
mavlink_msg_request_radio_calibration_pack(mavlink_system.sysid, mavlink_system.compid, &msg, unused);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE REQUEST_RADIO_CALIBRATION UNPACKING
/**
* @brief Get field unused from request_radio_calibration message
*
* @return Unused field. Included to prevent compile time warnings
*/
static inline uint8_t mavlink_msg_request_radio_calibration_get_unused(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
static inline void mavlink_msg_request_radio_calibration_decode(const mavlink_message_t* msg, mavlink_request_radio_calibration_t* request_radio_calibration)
{
request_radio_calibration->unused = mavlink_msg_request_radio_calibration_get_unused(msg);
}
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, February 15 2011, 15:58 UTC
* Generated on Thursday, March 31 2011, 22:06 UTC
*/
#ifndef UALBERTA_H
#define UALBERTA_H
......
......@@ -355,6 +355,11 @@
<field name="ack" type="uint8_t">0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control</field>
</message>
<message name="AUTH_KEY" id="7">
<description>Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.</description>
<field name="key" type="char[32]">key</field>
</message>
<message name="ACTION_ACK" id="9">
<description>This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<field name="action" type="uint8_t">The action id</field>
......@@ -463,14 +468,23 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
</message>
<message name="RAW_PRESSURE" id="29">
<description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, unscaled ADC values.</description>
<description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="press_abs" type="int16_t">Absolute pressure (raw)</field>
<field name="press_diff1" type="int16_t">Differential pressure 1 (raw)</field>
<field name="press_diff2" type="int16_t">Differential pressure 2 (raw)</field>
<field name="temperature" type="int16_t">Raw Temperature measurement (raw)</field>
</message>
<message name="SCALED_PRESSURE" id="38">
<description>The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="press_abs" type="float">Absolute pressure (hectopascal)</field>
<field name="press_diff1" type="float">Differential pressure 1 (hectopascal)</field>
<field name="press_diff2" type="float">Differential pressure 2 (hectopascal)</field>
<field name="temperature" type="int16_t">Raw Temperature measurement (0.01 degrees celsius per tick is default unit)</field>
<field name="press_diff" type="float">Differential pressure 1 (hectopascal)</field>
<field name="temperature" type="int16_t">Temperature measurement (0.01 degrees celsius)</field>
</message>
<message name="ATTITUDE" id="30">
<description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
......@@ -493,6 +507,7 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
<field name="vz" type="float">Z Speed</field>
</message>
<message name="GLOBAL_POSITION" id="33">
<description>The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
......@@ -640,9 +655,9 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
<description>As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="latitude" type="uint32_t">global position * 1E7</field>
<field name="longitude" type="uint32_t">global position * 1E7</field>
<field name="altitude" type="uint32_t">global position * 1000</field>
<field name="latitude" type="int32_t">global position * 1E7</field>
<field name="longitude" type="int32_t">global position * 1E7</field>
<field name="altitude" type="int32_t">global position * 1000</field>
</message>
<message name="GPS_LOCAL_ORIGIN_SET" id="49">
......
......@@ -69,29 +69,6 @@
<field name="diagSh2" type="int16_t">Diagnostic short 2</field>
<field name="diagSh3" type="int16_t">Diagnostic short 3</field>
</message>
<message name="PILOT_CONSOLE" id="174">
Pilot console PWM messges.
<field name="dt" type="uint16_t">Pilot's console throttle command </field>
<field name="dla" type="uint16_t">Pilot's console left aileron command </field>
<field name="dra" type="uint16_t">Pilot's console right aileron command </field>
<field name="dr" type="uint16_t">Pilot's console rudder command </field>
<field name="de" type="uint16_t">Pilot's console elevator command </field>
</message>
<message name="PWM_COMMANDS" id="175">
PWM Commands from the AP to the control surfaces.
<field name="dt_c" type="uint16_t">AutoPilot's throttle command </field>
<field name="dla_c" type="uint16_t">AutoPilot's left aileron command </field>
<field name="dra_c" type="uint16_t">AutoPilot's right aileron command </field>
<field name="dr_c" type="uint16_t">AutoPilot's rudder command </field>
<field name="dle_c" type="uint16_t">AutoPilot's left elevator command </field>
<field name="dre_c" type="uint16_t">AutoPilot's right elevator command </field>
<field name="dlf_c" type="uint16_t">AutoPilot's left flap command </field>
<field name="drf_c" type="uint16_t">AutoPilot's right flap command </field>
<field name="aux1" type="uint16_t">AutoPilot's aux1 command </field>
<field name="aux2" type="uint16_t">AutoPilot's aux2 command </field>
</message>
<message name="SLUGS_NAVIGATION" id="176">
Data used in the navigation algorithm.
......@@ -116,19 +93,6 @@
<field name="fl_6" type="float">Log value 6 </field>
</message>
<message name="FILTERED_DATA" id="178">
Measured value from the IMU in units after sensor calibration and temperature compensation. Note that this IS NOT the output of the attitude filter, for that see messages 30 and 33.
<field name="aX" type="float">Accelerometer X value (m/s^2) </field>
<field name="aY" type="float">Accelerometer Y value (m/s^2)</field>
<field name="aZ" type="float">Accelerometer Z value (m/s^2)</field>
<field name="gX" type="float">Gyro X value (rad/s) </field>
<field name="gY" type="float">Gyro Y value (rad/s)</field>
<field name="gZ" type="float">Gyro Z value (rad/s)</field>
<field name="mX" type="float">Magnetometer X (normalized to 1) </field>
<field name="mY" type="float">Magnetometer Y (normalized to 1) </field>
<field name="mZ" type="float">Magnetometer Z (normalized to 1) </field>
</message>
<message name="GPS_DATE_TIME" id="179">
Pilot console PWM messges.
<field name="year" type="uint8_t">Year reported by Gps </field>
......@@ -166,14 +130,6 @@ This message configures the Selective Passthrough mode. it allows to select whic
<field name="bitfieldPt" type="uint16_t">Bitfield containing the PT configuration</field>
</message>
<message name="PID" id="182">
Configure a PID loop.
<field name="target" type="uint8_t">The system setting the PID values</field>
<field name="pVal" type="float">Proportional gain</field>
<field name="iVal" type="float">Integral gain</field>
<field name="dVal" type="float">Derivative gain</field>
<field name="idx" type="uint8_t">PID loop index</field>
</message>
<message name="SLUGS_ACTION" id="183">
Action messages focused on the SLUGS AP.
......
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