diff --git a/.gitignore b/.gitignore index 3d8652cc44e404dedfd684779f90b21d388f24b6..a294f37fbb6c921c73026f59b96db667fc64190a 100644 --- a/.gitignore +++ b/.gitignore @@ -44,4 +44,7 @@ user_config.pri *.cproject *.sln *.suo -*thirdParty* + +thirdParty/qserialport-build-desktop/ +thirdParty/qserialport/bin/ +thirdParty/qserialport/lib/ diff --git a/.gitmodules b/.gitmodules deleted file mode 100644 index 813caa62ffee1d22cca538c4f25a14cdb44c2f48..0000000000000000000000000000000000000000 --- a/.gitmodules +++ /dev/null @@ -1,6 +0,0 @@ -[submodule "thirdParty/mavlink"] - path = thirdParty/mavlink - url = https://github.com/pixhawk/mavlink.git -[submodule "thirdParty/qserial"] - path = thirdParty/qserial - url = git://gitorious.org/inbiza-labs/qserialport.git diff --git a/CMakeLists.txt b/CMakeLists.txt index 518d12ab8dece710e2bf8fa2850da27719c7fddf..8259b663b20edf46a79b0c94c8b84b8a2f8a90b5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required (VERSION 2.6) project (qgroundcontrol) # marcos -macro(find_or_build_from_source PACKAGE PACKAGE_PATH IS_GIT_SUBMODULE) +macro(find_or_build_from_source PACKAGE PACKAGE_PATH) add_custom_target(${PACKAGE}) if (NOT ${PACKAGE}_BUILD_FROM_SOURCE) find_package(${PACKAGE}) @@ -14,11 +14,6 @@ macro(find_or_build_from_source PACKAGE PACKAGE_PATH IS_GIT_SUBMODULE) add_custom_target(${PACKAGE}_BUILD DEPENDS ${PACKAGE}_BUILD.stamp) add_dependencies(${PACKAGE} ${PACKAGE}_BUILD) set(${PACKAGE}_FOUND TRUE) - if (${IS_GIT_SUBMODULE}) - message(STATUS "${PACKAGE} detected as git submodule, will attempt to initialize it") - list(APPEND GIT_SUBMODULES ${PACKAGE_PATH}) - add_dependencies(${PACKAGE}_BUILD GIT) - endif() endif() endmacro(find_or_build_from_source) @@ -103,18 +98,6 @@ include(CPack) # add make dist target add_custom_target(dist COMMAND ${CMAKE_MAKE_PROGRAM} package_source) -# git submodules -if(IS_DIRECTORY ${PROJECT_SOURCE_DIR}/.git) - message(STATUS "git repository detected, will attempt to load submodules") - set(FOUND_GIT_REPO TRUE) - add_custom_command(OUTPUT GIT.stamp - COMMAND cd ${PROJECT_SOURCE_DIR} && git submodule init ${GIT_SUBMODULES} - COMMAND cd ${PROJECT_SOURCE_DIR} && git submodule update ${GIT_SUBMODULES}) - add_custom_target(GIT DEPENDS GIT.stamp) -else() - set(FOUND_GIT_REPO FALSE) -endif() - # find libraries with cmake modules find_package(Qt4 COMPONENTS QtGui QtCore QtNetwork QtOpenGL QtSVG QtXML QtPhonon QtWebKit REQUIRED) set(PHONON_FIND_QUIETLY FALSE) @@ -131,8 +114,8 @@ else() set(OPENSCENEGRAPH_FOUND TRUE) endif() -find_or_build_from_source(MAVLINK thirdParty/mavlink FOUND_GIT_REPO) -find_or_build_from_source(QSERIAL thirdParty/qserial FOUND_GIT_REPO) +find_or_build_from_source(MAVLINK thirdParty/mavlink) +find_or_build_from_source(QSERIALPORT thirdParty/qserialport) # build libraries from source if not found on system if(MAVLINK_BUILD_FROM_SOURCE) @@ -149,15 +132,67 @@ if(MAVLINK_BUILD_FROM_SOURCE) COMMAND touch MAVLINK_BUILD.stamp) endif() -if(QSERIAL_BUILD_FROM_SOURCE) - set(QSERIAL_INCLUDE_DIRS - ${PROJECT_SOURCE_DIR}/thirdParty/qserial/include - ${PROJECT_SOURCE_DIR}/thirdParty/qserial/include/QtSerialPort - ${PROJECT_SOURCE_DIR}/thirdParty/qserial/src +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 + ) + # 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 + ) + # qserialport src + set (qserialportSrc + thirdParty/qserialport/src/common/qserialport.cpp + thirdParty/qserialport/src/common/qportsettings.cpp + ) + + # qserialport native code + if (WIN32) + list(APPEND qserialportHdrs + thirdParty/qserialport/src/win32/commdcbhelper.h + ) + list(APPEND qserialportMocSrc + thirdParty/qserialport/src/win32/qwincommevtnotifier.h + thirdParty/qserialport/src/win32/wincommevtbreaker.h ) - set(QSERIAL_LIBRARIES qserial) - add_custom_command(OUTPUT QSERIAL_BUILD.stamp - COMMAND touch QSERIAL_BUILD.stamp) + 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 qserialportHdrs + thirdParty/qserialport/src/posix/termioshelper.h + ) + list(APPEND qserialportSrc + thirdParty/qserialport/src/posix/termioshelper.cpp + thirdParty/qserialport/src/posix/qserialportnative_posix.cpp + ) + else() + message(FATAL_ERROR "unknown OS") + endif() + + # qserialport linking + qt4_wrap_cpp(qserialportMoc ${qserialportMocSrc}) + add_library(qserialport ${qserialportMoc} ${qserialportSrc}) + target_link_libraries(qserialport ${QT_LIBRARIES}) + + set(QSERIALPORT_INCLUDE_DIRS + ${PROJECT_SOURCE_DIR}/thirdParty/qserialport/include + ${PROJECT_SOURCE_DIR}/thirdParty/qserialport/include/QtSerialPort + ${PROJECT_SOURCE_DIR}/thirdParty/qserialport/src + ) + set(QSERIALPORT_LIBRARIES qserialport) + add_custom_command(OUTPUT qserialport_BUILD.stamp + COMMAND touch qserialport_BUILD.stamp) endif() # data directory @@ -214,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}") @@ -785,61 +820,6 @@ qt4_wrap_cpp(qextserialportMoc ${qextserialportMocSrc}) add_library(qextserialport ${qextserialportMoc} ${qextserialportSrc}) target_link_libraries(qextserialport ${QT_LIBRARIES}) -# qserial library -#---------------------------------------------------------------------------- - -# 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 - ) -# 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 - ) -# qserial src -set (qserialSrc - thirdParty/qserial/src/common/qserialport.cpp - thirdParty/qserial/src/common/qportsettings.cpp -) - -# qserial native code -if (WIN32) - list(APPEND qserialHdrs - thirdParty/qserial/src/win32/commdcbhelper.h - ) - list(APPEND qserialMocSrc - thirdParty/qserial/src/win32/qwincommevtnotifier.h - thirdParty/qserial/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 - ) -elseif(UNIX OR APPLE) - list(APPEND qserialHdrs - thirdParty/qserial/src/posix/termioshelper.h - ) - list(APPEND qserialSrc - thirdParty/qserial/src/posix/termioshelper.cpp - thirdParty/qserial/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}) - # qmapcontrol library #---------------------------------------------------------------------------- diff --git a/CMakeModules/FindQSERIAL.cmake b/CMakeModules/FindQSERIALPORT.cmake similarity index 55% rename from CMakeModules/FindQSERIAL.cmake rename to CMakeModules/FindQSERIALPORT.cmake index e492d6f7ae33e40e1b80d3406c8e0ae43f678d4b..ae36f7e5fa589ca7188dcc2e6301c0d69faaca25 100644 --- a/CMakeModules/FindQSERIAL.cmake +++ b/CMakeModules/FindQSERIALPORT.cmake @@ -1,14 +1,14 @@ -# - 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) diff --git a/autobuild.sh b/autobuild.sh index f21ecf824c146ffc3346667cd744071b5764ac9a..e27559f2b11b3e1f96c2b6b40f05afe271df8c52 100755 --- a/autobuild.sh +++ b/autobuild.sh @@ -18,12 +18,12 @@ do if [ $OPT = "in_source_build" ] &> /dev/null then echo you chose in source build - mkdir -p build && cd build && cmake -DIN_SRC_BUILD:bool=TRUE .. && make $MAKEARGS + git submodule init && git submodule update && mkdir -p build && cd build && cmake -DIN_SRC_BUILD:bool=TRUE .. && make $MAKEARGS exit 0 elif [ $OPT = "install_build" ] &> /dev/null then echo you chose install build - mkdir -p build && cd build && cmake .. && make $MAKEARGS + git submodule init && git submodule update mkdir -p build && cd build && cmake .. && make $MAKEARGS exit 0 elif [ $OPT = "grab_debian_dependencies" ] &> /dev/null then @@ -40,13 +40,13 @@ do elif [ $OPT = "package_source" ] &> /dev/null then echo you chose to package the source - mkdir -p build && cd build && cmake .. && make package_source + git submodule init && git submodule update && mkdir -p build && cd build && cmake .. && make package_source exit 0 elif [ $OPT = "package" ] &> /dev/null then echo you chose to package the binary - mkdir -p build && cd build && cmake .. && make package + git submodule init && git submodule update && mkdir -p build && cd build && cmake .. && make package exit 0 elif [ $OPT = "clean" ] &> /dev/null diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 59924507c88abbe19a243b0bc2648778d94e15f9..531da7d9e9aec39856eb786f5e822477d5f719a2 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -59,36 +59,47 @@ exists(user_config.pri) { } INCLUDEPATH += $$BASEDIR/../mavlink/include/common +INCLUDEPATH += $$BASEDIR/../mavlink/include +INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include/common +INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include contains(MAVLINK_CONF, pixhawk) { # Remove the default set - it is included anyway INCLUDEPATH -= $$BASEDIR/../mavlink/include/common + INCLUDEPATH -= $$BASEDIR/thirdParty/mavlink/include/common # PIXHAWK SPECIAL MESSAGES INCLUDEPATH += $$BASEDIR/../mavlink/include/pixhawk + INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include/pixhawk DEFINES += QGC_USE_PIXHAWK_MESSAGES } contains(MAVLINK_CONF, slugs) { # Remove the default set - it is included anyway INCLUDEPATH -= $$BASEDIR/../mavlink/include/common + INCLUDEPATH -= $$BASEDIR/thirdParty/mavlink/include/common # SLUGS SPECIAL MESSAGES INCLUDEPATH += $$BASEDIR/../mavlink/include/slugs + INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include/slugs DEFINES += QGC_USE_SLUGS_MESSAGES } contains(MAVLINK_CONF, ualberta) { # Remove the default set - it is included anyway INCLUDEPATH -= $$BASEDIR/../mavlink/include/common + INCLUDEPATH -= $$BASEDIR/thirdParty/mavlink/include/common # UALBERTA SPECIAL MESSAGES INCLUDEPATH += $$BASEDIR/../mavlink/include/ualberta + INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include/ualberta DEFINES += QGC_USE_UALBERTA_MESSAGES } contains(MAVLINK_CONF, ardupilotmega) { # Remove the default set - it is included anyway INCLUDEPATH -= $$BASEDIR/../mavlink/include/common + INCLUDEPATH -= $$BASEDIR/thirdParty/mavlink/include/common # UALBERTA SPECIAL MESSAGES INCLUDEPATH += $$BASEDIR/../mavlink/include/ardupilotmega + INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include/ardupilotmega DEFINES += QGC_USE_ARDUPILOTMEGA_MESSAGES } @@ -98,13 +109,6 @@ contains(MAVLINK_CONF, ardupilotmega) { # done by the plugins above include(qgroundcontrol.pri) -# QWT plot and QExtSerial depend on paths set by qgroundcontrol.pri -# Include serial port library -include(src/lib/qextserialport/qextserialport.pri) - -# include qserial library -include(thirdParty/qserial/qserialport.prf) - # Include QWT plotting library include(src/lib/qwt/qwt.pri) DEPENDPATH += . \ @@ -112,11 +116,22 @@ DEPENDPATH += . \ # lib/QMapControl/src \ lib/opmapcontrol \ lib/opmapcontrol/src \ - plugins + plugins \ + thirdParty/qserialport/include \ + thirdParty/qserialport/include/QtSerialPort \ + thirdParty/qserialport INCLUDEPATH += . \ # lib/QMapControl \ lib/opmapcontrol \ - $$BASEDIR/../mavlink/include + thirdParty/qserialport/include \ + thirdParty/qserialport/include/QtSerialPort \ + thirdParty/qserialport/src + +# Include serial port library +include(src/lib/qextserialport/qextserialport.pri) +# include qserial library +include(thirdParty/qserialport/qgroundcontrol-qserialport.pri) + # ../mavlink/include \ # MAVLink/include \ diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 0c43dbd6e07039c4f96c598fc85b42f50f3c8600..9c1390adde19cbfc4ef1ac184f09400681cd713e 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -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 */ diff --git a/src/comm/SerialInterface.h b/src/comm/SerialInterface.h index 4eb3ca80c1e39c48cde9daec77ec335ccf961a35..630f93f0401663352abc5b85f1745b7b581cb016 100644 --- a/src/comm/SerialInterface.h +++ b/src/comm/SerialInterface.h @@ -49,7 +49,8 @@ signals: public: - enum baudRateType { + enum baudRateType + { BAUD50, //POSIX ONLY BAUD75, //POSIX ONLY BAUD110, @@ -77,14 +78,16 @@ public: BAUD921600 // WINDOWS ONLY }; - enum dataBitsType { + enum dataBitsType + { DATA_5, DATA_6, DATA_7, DATA_8 }; - enum parityType { + enum parityType + { PAR_NONE, PAR_ODD, PAR_EVEN, @@ -92,13 +95,15 @@ public: PAR_SPACE }; - enum stopBitsType { + enum stopBitsType + { STOP_1, STOP_1_5, //WINDOWS ONLY STOP_2 }; - enum flowType { + enum flowType + { FLOW_OFF, FLOW_HARDWARE, FLOW_XONXOFF @@ -107,7 +112,8 @@ public: /** * structure to contain port settings */ - struct portSettings { + struct portSettings + { baudRateType BaudRate; dataBitsType DataBits; parityType Parity; @@ -186,10 +192,11 @@ public: } virtual void setTimeout(qint64 timeout) { _port->setTimeout(timeout); - }; + } virtual void setFlow(SerialInterface::flowType flow) { // TODO implement - }; + _port->setFlowControl((FlowType)flow); + } }; using namespace TNX; @@ -262,11 +269,11 @@ public: virtual void setTimeout(qint64 timeout) { // TODO implement //_port->setTimeout(timeout); - }; + } virtual void setFlow(SerialInterface::flowType flow) { // TODO map settings.setFlowControl(QPortSettings::FLOW_OFF); - }; + } }; #endif // SERIALINTERFACE_H diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index d729b2d09e8715cedab2a2a5c9b2c8e60030ce6a..bffdddcaec4e161fb428f7bf907ee52ec95d97ec 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -48,32 +48,14 @@ SerialLink::SerialLink(QString portname, SerialInterface::baudRateType baudrate, this->timeout = 1; ///< The timeout controls how long the program flow should wait for new serial bytes. As we're polling, we don't want to wait at all. // Set the port name - if (porthandle == "") { - // name = tr("serial link ") + QString::number(getId()) + tr(" (unconfigured)"); + if (porthandle == "") + { name = tr("Serial Link ") + QString::number(getId()); - } else { - name = portname.trimmed(); } - -#ifdef _WIN3232 - // Windows 32bit & 64bit serial connection - winPort = CreateFile(porthandle, - GENERIC_READ | GENERIC_WRITE, - 0, - 0, - OPEN_EXISTING, - FILE_ATTRIBUTE_NORMAL, - 0); - if(winPort==INVALID_HANDLE_VALUE) { - if(GetLastError()==ERROR_FILE_NOT_FOUND) { - //serial port does not exist. Inform user. - } - //some other error occurred. Inform user. + else + { + name = portname.trimmed(); } -#else - -#endif - loadSettings(); } diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index a7399ea25135fe3e24649bde76a04bb7cbd050e6..20423372b40e5af2a2c11a944c5bbcb96888f7e0 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -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); } diff --git a/thirdParty/fetchUpstream.sh b/thirdParty/fetchUpstream.sh new file mode 100755 index 0000000000000000000000000000000000000000..bc07d8b34a7ca701dfb42505520cf1980c0a35ff --- /dev/null +++ b/thirdParty/fetchUpstream.sh @@ -0,0 +1,51 @@ +#!/bin/bash + +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 +} + +function fetch_mavlink +{ + echo + rm -rf mavlink + git clone git@github.com:openmav/mavlink.git + rm -rf mavlink/.git +} + +echo +select OPT in $LIST +do + case $OPT in + "qserialport") + fetch_qserialport + exit 0 + ;; + "mavlink") + fetch_mavlink + exit 0 + ;; + "all") + fetch_mavlink + fetch_qserialport + exit 0 + ;; + "exit") + exit 0 + ;; + *) + echo unknown option + exit 1 + esac +done + + diff --git a/thirdParty/mavlink b/thirdParty/mavlink deleted file mode 160000 index d2803c5eddbb30a14731c403a96f7a200318e50f..0000000000000000000000000000000000000000 --- a/thirdParty/mavlink +++ /dev/null @@ -1 +0,0 @@ -Subproject commit d2803c5eddbb30a14731c403a96f7a200318e50f diff --git a/thirdParty/mavlink/.gitignore b/thirdParty/mavlink/.gitignore new file mode 100644 index 0000000000000000000000000000000000000000..d67b9114a8bfd87e59462c81db271ba1cdc24f2f --- /dev/null +++ b/thirdParty/mavlink/.gitignore @@ -0,0 +1,3 @@ +*~ +doc/html +doc/*.log diff --git a/thirdParty/mavlink/README b/thirdParty/mavlink/README new file mode 100644 index 0000000000000000000000000000000000000000..513d5c77f7116429ed650d349f1ec155cf16ddac --- /dev/null +++ b/thirdParty/mavlink/README @@ -0,0 +1,29 @@ +MAVLink Micro Air Vehicle Message Marshalling Library + +This is a library for lightweight communication between +Micro Air Vehicles (swarm) and/or ground control stations. +It serializes C-structs for serial channels and can be used with +any type of radio modem. + +For help, please visit the mailing list: http://groups.google.com/group/mavlink + +MAVLink is licensed under the terms of the Lesser General Public License of the Free Software Foundation (LGPL). +As MAVLink is a header-only library, compiling an application with it is considered "using the libary", not a derived work. MAVLink can therefore be used without limits in any closed-source application without publishing the source code of the closed-source application. + +To generate/update packets, select mavlink_standard_message.xml +in the QGroundControl station settings view, select mavlink/include as +the output directory and click on "Save and Generate". +You will find the newly generated/updated message_xx.h files in +the mavlink/include/generated folder. + +To use MAVLink, #include the file, not the individual +message files. In some cases you will have to add the main folder to the include search path as well. To be safe, we recommend these flags: + +gcc -I mavlink/include -I mavlink/include/ + +For more information, please visit: + +http://qgroundcontrol.org/mavlink/ + +(c) 2009-2011 Lorenz Meier + diff --git a/thirdParty/mavlink/doc/Doxyfile b/thirdParty/mavlink/doc/Doxyfile new file mode 100755 index 0000000000000000000000000000000000000000..4ab7c0e06f50e2cc1c707636f45726291afa3deb --- /dev/null +++ b/thirdParty/mavlink/doc/Doxyfile @@ -0,0 +1,1521 @@ +# Doxyfile 1.6.1 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project +# +# All text after a hash (#) is considered a comment and will be ignored +# The format is: +# TAG = value [value, ...] +# For lists items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (" ") + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file +# that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# http://www.gnu.org/software/libiconv for the list of possible encodings. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded +# by quotes) that should identify the project. + +PROJECT_NAME = "PIXHAWK IMU / Autopilot" + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. +# This could be handy for archiving the generated documentation or +# if some version control system is used. + +PROJECT_NUMBER = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) +# base path where the generated documentation will be put. +# If a relative path is entered, it will be relative to the location +# where doxygen was started. If left blank the current directory will be used. + +OUTPUT_DIRECTORY = + +# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create +# 4096 sub-directories (in 2 levels) under the output directory of each output +# format and will distribute the generated files over these directories. +# Enabling this option can be useful when feeding doxygen a huge amount of +# source files, where putting all generated files in the same directory would +# otherwise cause performance problems for the file system. + +CREATE_SUBDIRS = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# The default language is English, other supported languages are: +# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, +# Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German, +# Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English +# messages), Korean, Korean-en, Lithuanian, Norwegian, Macedonian, Persian, +# Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrilic, Slovak, +# Slovene, Spanish, Swedish, Ukrainian, and Vietnamese. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will +# include brief member descriptions after the members that are listed in +# the file and class documentation (similar to JavaDoc). +# Set to NO to disable this. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend +# the brief description of a member or function before the detailed description. +# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator +# that is used to form the text in various listings. Each string +# in this list, if found as the leading text of the brief description, will be +# stripped from the text and the result after processing the whole list, is +# used as the annotated text. Otherwise, the brief description is used as-is. +# If left blank, the following values are used ("$name" is automatically +# replaced with the name of the entity): "The $name class" "The $name widget" +# "The $name file" "is" "provides" "specifies" "contains" +# "represents" "a" "an" "the" + +ABBREVIATE_BRIEF = + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# Doxygen will generate a detailed section even if there is only a brief +# description. + +ALWAYS_DETAILED_SEC = YES + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. + +INLINE_INHERITED_MEMB = YES + +# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full +# path before files name in the file list and in the header files. If set +# to NO the shortest path that makes the file name unique will be used. + +FULL_PATH_NAMES = NO + +# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag +# can be used to strip a user-defined part of the path. Stripping is +# only done if one of the specified strings matches the left-hand part of +# the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the +# path to strip. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of +# the path mentioned in the documentation of a class, which tells +# the reader which header file to include in order to use a class. +# If left blank only the name of the header file containing the class +# definition is used. Otherwise one should specify the include paths that +# are normally passed to the compiler using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter +# (but less readable) file names. This can be useful is your file systems +# doesn't support long names like on DOS, Mac, or CD-ROM. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen +# will interpret the first line (until the first dot) of a JavaDoc-style +# comment as the brief description. If set to NO, the JavaDoc +# comments will behave just like regular Qt-style comments +# (thus requiring an explicit @brief command for a brief description.) + +JAVADOC_AUTOBRIEF = NO + +# If the QT_AUTOBRIEF tag is set to YES then Doxygen will +# interpret the first line (until the first dot) of a Qt-style +# comment as the brief description. If set to NO, the comments +# will behave just like regular Qt-style comments (thus requiring +# an explicit \brief command for a brief description.) + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen +# treat a multi-line C++ special comment block (i.e. a block of //! or /// +# comments) as a brief description. This used to be the default behaviour. +# The new default is to treat a multi-line C++ comment block as a detailed +# description. Set this tag to YES if you prefer the old behaviour instead. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented +# member inherits the documentation from any documented member that it +# re-implements. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce +# a new page for each member. If set to NO, the documentation of a member will +# be part of the file/class/namespace that contains it. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. +# Doxygen uses this value to replace tabs by spaces in code fragments. + +TAB_SIZE = 8 + +# This tag can be used to specify a number of aliases that acts +# as commands in the documentation. An alias has the form "name=value". +# For example adding "sideeffect=\par Side Effects:\n" will allow you to +# put the command \sideeffect (or @sideeffect) in the documentation, which +# will result in a user-defined paragraph with heading "Side Effects:". +# You can put \n's in the value part of an alias to insert newlines. + +ALIASES = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C +# sources only. Doxygen will then generate output that is more tailored for C. +# For instance, some of the names that are used will be different. The list +# of all members will be omitted, etc. + +OPTIMIZE_OUTPUT_FOR_C = YES + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java +# sources only. Doxygen will then generate output that is more tailored for +# Java. For instance, namespaces will be presented as packages, qualified +# scopes will look different, etc. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources only. Doxygen will then generate output that is more tailored for +# Fortran. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for +# VHDL. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Doxygen selects the parser to use depending on the extension of the files it parses. +# With this tag you can assign which parser to use for a given extension. +# Doxygen has a built-in mapping, but you can override or extend it using this tag. +# The format is ext=language, where ext is a file extension, and language is one of +# the parsers supported by doxygen: IDL, Java, Javascript, C#, C, C++, D, PHP, +# Objective-C, Python, Fortran, VHDL, C, C++. For instance to make doxygen treat +# .inc files as Fortran files (default is PHP), and .f files as C (default is Fortran), +# use: inc=Fortran f=C. Note that for custom extensions you also need to set FILE_PATTERNS otherwise the files are not read by doxygen. + +EXTENSION_MAPPING = + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should +# set this tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); v.s. +# func(std::string) {}). This also make the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip sources only. +# Doxygen will parse them like normal C++ but will assume all classes use public +# instead of private inheritance when no explicit protection keyword is present. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate getter +# and setter methods for a property. Setting this option to YES (the default) +# will make doxygen to replace the get and set methods by a property in the +# documentation. This will only work if the methods are indeed getting or +# setting a simple type. If this is not the case, or you want to show the +# methods anyway, you should set this option to NO. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES, then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. + +DISTRIBUTE_GROUP_DOC = NO + +# Set the SUBGROUPING tag to YES (the default) to allow class member groups of +# the same type (for instance a group of public functions) to be put as a +# subgroup of that type (e.g. under the Public Functions section). Set it to +# NO to prevent subgrouping. Alternatively, this can be done per class using +# the \nosubgrouping command. + +SUBGROUPING = YES + +# When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum +# is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically +# be useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. + +TYPEDEF_HIDES_STRUCT = NO + +# The SYMBOL_CACHE_SIZE determines the size of the internal cache use to +# determine which symbols to keep in memory and which to flush to disk. +# When the cache is full, less often used symbols will be written to disk. +# For small to medium size projects (<1000 input files) the default value is +# probably good enough. For larger projects a too small cache size can cause +# doxygen to be busy swapping symbols to and from disk most of the time +# causing a significant performance penality. +# If the system has enough physical memory increasing the cache will improve the +# performance by keeping more symbols in memory. Note that the value works on +# a logarithmic scale so increasing the size by one will rougly double the +# memory usage. The cache size is given by this formula: +# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, +# corresponding to a cache size of 2^16 = 65536 symbols + +SYMBOL_CACHE_SIZE = 0 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# documentation are documented, even if no documentation was available. +# Private class members and static file members will be hidden unless +# the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES + +EXTRACT_ALL = YES + +# If the EXTRACT_PRIVATE tag is set to YES all private members of a class +# will be included in the documentation. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_STATIC tag is set to YES all static members of a file +# will be included in the documentation. + +EXTRACT_STATIC = YES + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) +# defined locally in source files will be included in the documentation. +# If set to NO only classes defined in header files are included. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. When set to YES local +# methods, which are defined in the implementation section but not in +# the interface are included in the documentation. +# If set to NO (the default) only methods in the interface are included. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base +# name of the file that contains the anonymous namespace. By default +# anonymous namespace are hidden. + +EXTRACT_ANON_NSPACES = NO + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all +# undocumented members of documented classes, files or namespaces. +# If set to NO (the default) these members will be included in the +# various overviews, but no documentation section is generated. +# This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. +# If set to NO (the default) these classes will be included in the various +# overviews. This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all +# friend (class|struct|union) declarations. +# If set to NO (the default) these declarations will be included in the +# documentation. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any +# documentation blocks found inside the body of a function. +# If set to NO (the default) these blocks will be appended to the +# function's detailed documentation block. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation +# that is typed after a \internal command is included. If the tag is set +# to NO (the default) then the documentation will be excluded. +# Set it to YES to include the internal documentation. + +INTERNAL_DOCS = NO + +# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate +# file names in lower-case letters. If set to YES upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. + +CASE_SENSE_NAMES = YES + +# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen +# will show members with their full class and namespace scopes in the +# documentation. If set to YES the scope will be hidden. + +HIDE_SCOPE_NAMES = NO + +# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen +# will put a list of the files that are included by a file in the documentation +# of that file. + +SHOW_INCLUDE_FILES = YES + +# If the INLINE_INFO tag is set to YES (the default) then a tag [inline] +# is inserted in the documentation for inline members. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen +# will sort the (detailed) documentation of file and class members +# alphabetically by member name. If set to NO the members will appear in +# declaration order. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the +# brief documentation of file, namespace and class members alphabetically +# by member name. If set to NO (the default) the members will appear in +# declaration order. + +SORT_BRIEF_DOCS = NO + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the (brief and detailed) documentation of class members so that constructors and destructors are listed first. If set to NO (the default) the constructors will appear in the respective orders defined by SORT_MEMBER_DOCS and SORT_BRIEF_DOCS. This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the +# hierarchy of group names into alphabetical order. If set to NO (the default) +# the group names will appear in their defined order. + +SORT_GROUP_NAMES = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be +# sorted by fully-qualified names, including namespaces. If set to +# NO (the default), the class list will be sorted only by class name, +# not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the +# alphabetical list. + +SORT_BY_SCOPE_NAME = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or +# disable (NO) the todo list. This list is created by putting \todo +# commands in the documentation. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or +# disable (NO) the test list. This list is created by putting \test +# commands in the documentation. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or +# disable (NO) the bug list. This list is created by putting \bug +# commands in the documentation. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or +# disable (NO) the deprecated list. This list is created by putting +# \deprecated commands in the documentation. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional +# documentation sections, marked by \if sectionname ... \endif. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines +# the initial value of a variable or define consists of for it to appear in +# the documentation. If the initializer consists of more lines than specified +# here it will be hidden. Use a value of 0 to hide initializers completely. +# The appearance of the initializer of individual variables and defines in the +# documentation can be controlled using \showinitializer or \hideinitializer +# command in the documentation regardless of this setting. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated +# at the bottom of the documentation of classes and structs. If set to YES the +# list will mention the files that were used to generate the documentation. + +SHOW_USED_FILES = YES + +# If the sources in your project are distributed over multiple directories +# then setting the SHOW_DIRECTORIES tag to YES will show the directory hierarchy +# in the documentation. The default is NO. + +SHOW_DIRECTORIES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. +# This will remove the Files entry from the Quick Index and from the +# Folder Tree View (if specified). The default is YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the +# Namespaces page. +# This will remove the Namespaces entry from the Quick Index +# and from the Folder Tree View (if specified). The default is YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command , where is the value of +# the FILE_VERSION_FILTER tag, and is the name of an input file +# provided by doxygen. Whatever the program writes to standard output +# is used as the file version. See the manual for examples. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed by +# doxygen. The layout file controls the global structure of the generated output files +# in an output format independent way. The create the layout file that represents +# doxygen's defaults, run doxygen with the -l option. You can optionally specify a +# file name after the option, if omitted DoxygenLayout.xml will be used as the name +# of the layout file. + +LAYOUT_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated +# by doxygen. Possible values are YES and NO. If left blank NO is used. + +QUIET = YES + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated by doxygen. Possible values are YES and NO. If left blank +# NO is used. + +WARNINGS = YES + +# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings +# for undocumented members. If EXTRACT_ALL is set to YES then this flag will +# automatically be disabled. + +WARN_IF_UNDOCUMENTED = YES + +# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some +# parameters in a documented function, or documenting parameters that +# don't exist or using markup commands wrongly. + +WARN_IF_DOC_ERROR = YES + +# This WARN_NO_PARAMDOC option can be abled to get warnings for +# functions that are documented, but have no documentation for their parameters +# or return value. If set to NO (the default) doxygen will only warn about +# wrong or incomplete parameter documentation, but not about the absence of +# documentation. + +WARN_NO_PARAMDOC = YES + +# The WARN_FORMAT tag determines the format of the warning messages that +# doxygen can produce. The string should contain the $file, $line, and $text +# tags, which will be replaced by the file and line number from which the +# warning originated and the warning text. Optionally the format may contain +# $version, which will be replaced by the version of the file (if it could +# be obtained via FILE_VERSION_FILTER) + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning +# and error messages should be written. If left blank the output is written +# to stderr. + +WARN_LOGFILE = doxy.log + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag can be used to specify the files and/or directories that contain +# documented source files. You may enter file names like "myfile.cpp" or +# directories like "/usr/src/myproject". Separate the files or directories +# with spaces. + +INPUT = .. + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is +# also the default input encoding. Doxygen uses libiconv (or the iconv built +# into libc) for the transcoding. See http://www.gnu.org/software/libiconv for +# the list of possible encodings. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank the following patterns are tested: +# *.c *.cc *.cxx *.cpp *.c++ *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh *.hxx +# *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.py *.f90 + +FILE_PATTERNS = *.c *.h *.hpp *.hxx *.cc *.cpp *.cxx *.dox +#FILE_PATTERNS = + +# The RECURSIVE tag can be used to turn specify whether or not subdirectories +# should be searched for input files as well. Possible values are YES and NO. +# If left blank NO is used. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. + +EXCLUDE = ../Debug \ + ../Release \ + ../external \ + ../testing \ + ../tools \ + ../arm7/include \ + ../measurements + +# The EXCLUDE_SYMLINKS tag can be used select whether or not files or +# directories that are symbolic links (a Unix filesystem feature) are excluded +# from the input. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. Note that the wildcards are matched +# against the file with absolute path, so to exclude all test directories +# for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# AClass::ANamespace, ANamespace::*Test + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or +# directories that contain example code fragments that are included (see +# the \include command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank all files are included. + +EXAMPLE_PATTERNS = + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude +# commands irrespective of the value of the RECURSIVE tag. +# Possible values are YES and NO. If left blank NO is used. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or +# directories that contain image that are included in the documentation (see +# the \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command , where +# is the value of the INPUT_FILTER tag, and is the name of an +# input file. Doxygen will then use the output that the filter program writes +# to standard output. +# If FILTER_PATTERNS is specified, this tag will be +# ignored. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. +# Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. +# The filters are a list of the form: +# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further +# info on how filters are used. If FILTER_PATTERNS is empty, INPUT_FILTER +# is applied to all files. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will be used to filter the input files when producing source +# files to browse (i.e. when SOURCE_BROWSER is set to YES). + +FILTER_SOURCE_FILES = NO + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will +# be generated. Documented entities will be cross-referenced with these sources. +# Note: To get rid of all source code in the generated output, make sure also +# VERBATIM_HEADERS is set to NO. + +SOURCE_BROWSER = YES + +# Setting the INLINE_SOURCES tag to YES will include the body +# of functions and classes directly in the documentation. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct +# doxygen to hide any special comment blocks from generated source code +# fragments. Normal C and C++ comments will always remain visible. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES +# then for each documented function all documented +# functions referencing it will be listed. + +REFERENCED_BY_RELATION = YES + +# If the REFERENCES_RELATION tag is set to YES +# then for each documented function all documented entities +# called/used by that function will be listed. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES (the default) +# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from +# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will +# link to the source code. +# Otherwise they will link to the documentation. + +REFERENCES_LINK_SOURCE = YES + +# If the USE_HTAGS tag is set to YES then the references to source code +# will point to the HTML generated by the htags(1) tool instead of doxygen +# built-in source browser. The htags tool is part of GNU's global source +# tagging system (see http://www.gnu.org/software/global/global.html). You +# will need version 4.8.6 or higher. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen +# will generate a verbatim copy of the header file for each class for +# which an include is specified. Set to NO to disable this. + +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index +# of all compounds will be generated. Enable this if the project +# contains a lot of classes, structs, unions or interfaces. + +ALPHABETICAL_INDEX = NO + +# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then +# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns +# in which this list will be split (can be a number in the range [1..20]) + +COLS_IN_ALPHA_INDEX = 5 + +# In case all classes in a project start with a common prefix, all +# classes will be put under the same header in the alphabetical index. +# The IGNORE_PREFIX tag can be used to specify one or more prefixes that +# should be ignored while generating the index headers. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES (the default) Doxygen will +# generate HTML output. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `html' will be used as the default path. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for +# each generated HTML page (for example: .htm,.php,.asp). If it is left blank +# doxygen will generate files with .html extension. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a personal HTML header for +# each generated HTML page. If it is left blank doxygen will generate a +# standard header. + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a personal HTML footer for +# each generated HTML page. If it is left blank doxygen will generate a +# standard footer. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading +# style sheet that is used by each HTML page. It can be used to +# fine-tune the look of the HTML output. If the tag is left blank doxygen +# will generate a default style sheet. Note that doxygen will try to copy +# the style sheet file to the HTML output directory, so don't put your own +# stylesheet in the HTML output directory as well, or it will be erased! + +HTML_STYLESHEET = + +# If the HTML_ALIGN_MEMBERS tag is set to YES, the members of classes, +# files or namespaces will be aligned in HTML using tables. If set to +# NO a bullet list will be used. + +HTML_ALIGN_MEMBERS = YES + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. For this to work a browser that supports +# JavaScript and DHTML is required (for instance Mozilla 1.0+, Firefox +# Netscape 6.0+, Internet explorer 5.0+, Konqueror, or Safari). + +HTML_DYNAMIC_SECTIONS = NO + +# If the GENERATE_DOCSET tag is set to YES, additional index files +# will be generated that can be used as input for Apple's Xcode 3 +# integrated development environment, introduced with OSX 10.5 (Leopard). +# To create a documentation set, doxygen will generate a Makefile in the +# HTML output directory. Running make will produce the docset in that +# directory and running "make install" will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find +# it at startup. +# See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html for more information. + +GENERATE_DOCSET = NO + +# When GENERATE_DOCSET tag is set to YES, this tag determines the name of the +# feed. A documentation feed provides an umbrella under which multiple +# documentation sets from a single provider (such as a company or product suite) +# can be grouped. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# When GENERATE_DOCSET tag is set to YES, this tag specifies a string that +# should uniquely identify the documentation set bundle. This should be a +# reverse domain-name style string, e.g. com.mycompany.MyDocSet. Doxygen +# will append .docset to the name. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# If the GENERATE_HTMLHELP tag is set to YES, additional index files +# will be generated that can be used as input for tools like the +# Microsoft HTML help workshop to generate a compiled HTML help file (.chm) +# of the generated HTML documentation. + +GENERATE_HTMLHELP = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can +# be used to specify the file name of the resulting .chm file. You +# can add a path in front of the file if the result should not be +# written to the html output directory. + +CHM_FILE = + +# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can +# be used to specify the location (absolute path including file name) of +# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run +# the HTML help compiler on the generated index.hhp. + +HHC_LOCATION = + +# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag +# controls if a separate .chi index file is generated (YES) or that +# it should be included in the master .chm file (NO). + +GENERATE_CHI = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_INDEX_ENCODING +# is used to encode HtmlHelp index (hhk), content (hhc) and project file +# content. + +CHM_INDEX_ENCODING = + +# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag +# controls whether a binary table of contents is generated (YES) or a +# normal table of contents (NO) in the .chm file. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members +# to the contents of the HTML help documentation and to the tree view. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and QHP_VIRTUAL_FOLDER +# are set, an additional index file will be generated that can be used as input for +# Qt's qhelpgenerator to generate a Qt Compressed Help (.qch) of the generated +# HTML documentation. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can +# be used to specify the file name of the resulting .qch file. +# The path specified is relative to the HTML output folder. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#namespace + +QHP_NAMESPACE = + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#virtual-folders + +QHP_VIRTUAL_FOLDER = doc + +# If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to add. +# For more information please see +# http://doc.trolltech.com/qthelpproject.html#custom-filters + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the custom filter to add.For more information please see +# Qt Help Project / Custom Filters. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this project's +# filter section matches. +# Qt Help Project / Filter Attributes. + +QHP_SECT_FILTER_ATTRS = + +# If the GENERATE_QHP tag is set to YES, the QHG_LOCATION tag can +# be used to specify the location of Qt's qhelpgenerator. +# If non-empty doxygen will try to run qhelpgenerator on the generated +# .qhp file. + +QHG_LOCATION = + +# The DISABLE_INDEX tag can be used to turn on/off the condensed index at +# top of each HTML page. The value NO (the default) enables the index and +# the value YES disables it. + +DISABLE_INDEX = NO + +# This tag can be used to set the number of enum values (range [1..20]) +# that doxygen will group on one line in the generated HTML documentation. + +ENUM_VALUES_PER_LINE = 4 + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. +# If the tag value is set to YES, a side panel will be generated +# containing a tree-like index structure (just like the one that +# is generated for HTML Help). For this to work a browser that supports +# JavaScript, DHTML, CSS and frames is required (i.e. any modern browser). +# Windows users are probably better off using the HTML help feature. + +GENERATE_TREEVIEW = NO + +# By enabling USE_INLINE_TREES, doxygen will generate the Groups, Directories, +# and Class Hierarchy pages using a tree view instead of an ordered list. + +USE_INLINE_TREES = NO + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be +# used to set the initial width (in pixels) of the frame in which the tree +# is shown. + +TREEVIEW_WIDTH = 250 + +# Use this tag to change the font size of Latex formulas included +# as images in the HTML documentation. The default is 10. Note that +# when you change the font size after a successful doxygen run you need +# to manually remove any form_*.png images from the HTML output directory +# to force them to be regenerated. + +FORMULA_FONTSIZE = 10 + +# When the SEARCHENGINE tag is enable doxygen will generate a search box for the HTML output. The underlying search engine uses javascript +# and DHTML and should work on any modern browser. Note that when using HTML help (GENERATE_HTMLHELP) or Qt help (GENERATE_QHP) +# there is already a search function so this one should typically +# be disabled. + +SEARCHENGINE = YES + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will +# generate Latex output. + +GENERATE_LATEX = NO + +# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `latex' will be used as the default path. + +LATEX_OUTPUT = latex + +# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be +# invoked. If left blank `latex' will be used as the default command name. + +LATEX_CMD_NAME = latex + +# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to +# generate index for LaTeX. If left blank `makeindex' will be used as the +# default command name. + +MAKEINDEX_CMD_NAME = makeindex + +# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact +# LaTeX documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_LATEX = NO + +# The PAPER_TYPE tag can be used to set the paper type that is used +# by the printer. Possible values are: a4, a4wide, letter, legal and +# executive. If left blank a4wide will be used. + +PAPER_TYPE = a4wide + +# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX +# packages that should be included in the LaTeX output. + +EXTRA_PACKAGES = + +# The LATEX_HEADER tag can be used to specify a personal LaTeX header for +# the generated latex document. The header should contain everything until +# the first chapter. If it is left blank doxygen will generate a +# standard header. Notice: only use this tag if you know what you are doing! + +LATEX_HEADER = + +# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated +# is prepared for conversion to pdf (using ps2pdf). The pdf file will +# contain links (just like the HTML output) instead of page references +# This makes the output suitable for online browsing using a pdf viewer. + +PDF_HYPERLINKS = YES + +# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of +# plain latex in the generated Makefile. Set this option to YES to get a +# higher quality PDF documentation. + +USE_PDFLATEX = YES + +# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. +# command to the generated LaTeX files. This will instruct LaTeX to keep +# running if errors occur, instead of asking the user for help. +# This option is also used when generating formulas in HTML. + +LATEX_BATCHMODE = NO + +# If LATEX_HIDE_INDICES is set to YES then doxygen will not +# include the index chapters (such as File Index, Compound Index, etc.) +# in the output. + +LATEX_HIDE_INDICES = NO + +# If LATEX_SOURCE_CODE is set to YES then doxygen will include source code with syntax highlighting in the LaTeX output. Note that which sources are shown also depends on other settings such as SOURCE_BROWSER. + +LATEX_SOURCE_CODE = NO + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- + +# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output +# The RTF output is optimized for Word 97 and may not look very pretty with +# other RTF readers or editors. + +GENERATE_RTF = NO + +# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `rtf' will be used as the default path. + +RTF_OUTPUT = rtf + +# If the COMPACT_RTF tag is set to YES Doxygen generates more compact +# RTF documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_RTF = NO + +# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated +# will contain hyperlink fields. The RTF file will +# contain links (just like the HTML output) instead of page references. +# This makes the output suitable for online browsing using WORD or other +# programs which support those fields. +# Note: wordpad (write) and others do not support links. + +RTF_HYPERLINKS = NO + +# Load stylesheet definitions from file. Syntax is similar to doxygen's +# config file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. + +RTF_STYLESHEET_FILE = + +# Set optional variables used in the generation of an rtf document. +# Syntax is similar to doxygen's config file. + +RTF_EXTENSIONS_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- + +# If the GENERATE_MAN tag is set to YES (the default) Doxygen will +# generate man pages + +GENERATE_MAN = NO + +# The MAN_OUTPUT tag is used to specify where the man pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `man' will be used as the default path. + +MAN_OUTPUT = man + +# The MAN_EXTENSION tag determines the extension that is added to +# the generated man pages (default is the subroutine's section .3) + +MAN_EXTENSION = .3 + +# If the MAN_LINKS tag is set to YES and Doxygen generates man output, +# then it will generate one additional man file for each entity +# documented in the real man page(s). These additional files +# only source the real man page, but without them the man command +# would be unable to find the correct page. The default is NO. + +MAN_LINKS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- + +# If the GENERATE_XML tag is set to YES Doxygen will +# generate an XML file that captures the structure of +# the code including all documentation. + +GENERATE_XML = NO + +# The XML_OUTPUT tag is used to specify where the XML pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `xml' will be used as the default path. + +XML_OUTPUT = xml + +# The XML_SCHEMA tag can be used to specify an XML schema, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_SCHEMA = + +# The XML_DTD tag can be used to specify an XML DTD, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_DTD = + +# If the XML_PROGRAMLISTING tag is set to YES Doxygen will +# dump the program listings (including syntax highlighting +# and cross-referencing information) to the XML output. Note that +# enabling this will significantly increase the size of the XML output. + +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will +# generate an AutoGen Definitions (see autogen.sf.net) file +# that captures the structure of the code including all +# documentation. Note that this feature is still experimental +# and incomplete at the moment. + +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- + +# If the GENERATE_PERLMOD tag is set to YES Doxygen will +# generate a Perl module file that captures the structure of +# the code including all documentation. Note that this +# feature is still experimental and incomplete at the +# moment. + +GENERATE_PERLMOD = NO + +# If the PERLMOD_LATEX tag is set to YES Doxygen will generate +# the necessary Makefile rules, Perl scripts and LaTeX code to be able +# to generate PDF and DVI output from the Perl module output. + +PERLMOD_LATEX = NO + +# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be +# nicely formatted so it can be parsed by a human reader. +# This is useful +# if you want to understand what is going on. +# On the other hand, if this +# tag is set to NO the size of the Perl module output will be much smaller +# and Perl will parse it just the same. + +PERLMOD_PRETTY = YES + +# The names of the make variables in the generated doxyrules.make file +# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. +# This is useful so different doxyrules.make files included by the same +# Makefile don't overwrite each other's variables. + +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will +# evaluate all C-preprocessor directives found in the sources and include +# files. + +ENABLE_PREPROCESSING = YES + +# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro +# names in the source code. If set to NO (the default) only conditional +# compilation will be performed. Macro expansion can be done in a controlled +# way by setting EXPAND_ONLY_PREDEF to YES. + +MACRO_EXPANSION = NO + +# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES +# then the macro expansion is limited to the macros specified with the +# PREDEFINED and EXPAND_AS_DEFINED tags. + +EXPAND_ONLY_PREDEF = NO + +# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files +# in the INCLUDE_PATH (see below) will be search if a #include is found. + +SEARCH_INCLUDES = YES + +# The INCLUDE_PATH tag can be used to specify one or more directories that +# contain include files that are not input files but should be processed by +# the preprocessor. + +INCLUDE_PATH = + +# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard +# patterns (like *.h and *.hpp) to filter out the header-files in the +# directories. If left blank, the patterns specified with FILE_PATTERNS will +# be used. + +INCLUDE_FILE_PATTERNS = + +# The PREDEFINED tag can be used to specify one or more macro names that +# are defined before the preprocessor is started (similar to the -D option of +# gcc). The argument of the tag is a list of macros of the form: name +# or name=definition (no spaces). If the definition and the = are +# omitted =1 is assumed. To prevent a macro definition from being +# undefined via #undef or recursively expanded use the := operator +# instead of the = operator. + +PREDEFINED = IMU_PIXHAWK_V200 IMU_PIXHAWK_V210 + +# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then +# this tag can be used to specify a list of macro names that should be expanded. +# The macro definition that is found in the sources will be used. +# Use the PREDEFINED tag if you want to use a different macro definition. + +EXPAND_AS_DEFINED = + +# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then +# doxygen's preprocessor will remove all function-like macros that are alone +# on a line, have an all uppercase name, and do not end with a semicolon. Such +# function macros are typically used for boiler-plate code, and will confuse +# the parser if not removed. + +SKIP_FUNCTION_MACROS = NO + +#--------------------------------------------------------------------------- +# Configuration::additions related to external references +#--------------------------------------------------------------------------- + +# The TAGFILES option can be used to specify one or more tagfiles. +# Optionally an initial location of the external documentation +# can be added for each tagfile. The format of a tag file without +# this location is as follows: +# +# TAGFILES = file1 file2 ... +# Adding location for the tag files is done as follows: +# +# TAGFILES = file1=loc1 "file2 = loc2" ... +# where "loc1" and "loc2" can be relative or absolute paths or +# URLs. If a location is present for each tag, the installdox tool +# does not have to be run to correct the links. +# Note that each tag file must have a unique name +# (where the name does NOT include the path) +# If a tag file is not located in the directory in which doxygen +# is run, you must also specify the path to the tagfile here. + +TAGFILES = + +# When a file name is specified after GENERATE_TAGFILE, doxygen will create +# a tag file that is based on the input files it reads. + +GENERATE_TAGFILE = + +# If the ALLEXTERNALS tag is set to YES all external classes will be listed +# in the class index. If set to NO only the inherited external classes +# will be listed. + +ALLEXTERNALS = NO + +# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed +# in the modules index. If set to NO, only the current project's groups will +# be listed. + +EXTERNAL_GROUPS = YES + +# The PERL_PATH should be the absolute path and name of the perl script +# interpreter (i.e. the result of `which perl'). + +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will +# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base +# or super classes. Setting the tag to NO turns the diagrams off. Note that +# this option is superseded by the HAVE_DOT option below. This is only a +# fallback. It is recommended to install and use dot, since it yields more +# powerful graphs. + +CLASS_DIAGRAMS = YES + +# You can define message sequence charts within doxygen comments using the \msc +# command. Doxygen will then run the mscgen tool (see +# http://www.mcternan.me.uk/mscgen/) to produce the chart and insert it in the +# documentation. The MSCGEN_PATH tag allows you to specify the directory where +# the mscgen tool resides. If left empty the tool is assumed to be found in the +# default search path. + +MSCGEN_PATH = + +# If set to YES, the inheritance and collaboration graphs will hide +# inheritance and usage relations if the target is undocumented +# or is not a class. + +HIDE_UNDOC_RELATIONS = YES + +# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is +# available from the path. This tool is part of Graphviz, a graph visualization +# toolkit from AT&T and Lucent Bell Labs. The other options in this section +# have no effect if this option is set to NO (the default) + +HAVE_DOT = YES + +# By default doxygen will write a font called FreeSans.ttf to the output +# directory and reference it in all dot files that doxygen generates. This +# font does not include all possible unicode characters however, so when you need +# these (or just want a differently looking font) you can specify the font name +# using DOT_FONTNAME. You need need to make sure dot is able to find the font, +# which can be done by putting it in a standard location or by setting the +# DOTFONTPATH environment variable or by setting DOT_FONTPATH to the directory +# containing the font. + +DOT_FONTNAME = FreeSans + +# The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs. +# The default size is 10pt. + +DOT_FONTSIZE = 10 + +# By default doxygen will tell dot to use the output directory to look for the +# FreeSans.ttf font (which doxygen will put there itself). If you specify a +# different font using DOT_FONTNAME you can set the path where dot +# can find it using this tag. + +DOT_FONTPATH = + +# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect inheritance relations. Setting this tag to YES will force the +# the CLASS_DIAGRAMS tag to NO. + +CLASS_GRAPH = YES + +# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect implementation dependencies (inheritance, containment, and +# class references variables) of the class with other documented classes. + +COLLABORATION_GRAPH = YES + +# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for groups, showing the direct groups dependencies + +GROUP_GRAPHS = YES + +# If the UML_LOOK tag is set to YES doxygen will generate inheritance and +# collaboration diagrams in a style similar to the OMG's Unified Modeling +# Language. + +UML_LOOK = NO + +# If set to YES, the inheritance and collaboration graphs will show the +# relations between templates and their instances. + +TEMPLATE_RELATIONS = NO + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT +# tags are set to YES then doxygen will generate a graph for each documented +# file showing the direct and indirect include dependencies of the file with +# other documented files. + +INCLUDE_GRAPH = YES + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and +# HAVE_DOT tags are set to YES then doxygen will generate a graph for each +# documented header file showing the documented files that directly or +# indirectly include this file. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH and HAVE_DOT options are set to YES then +# doxygen will generate a call dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable call graphs +# for selected functions only using the \callgraph command. + +CALL_GRAPH = NO + +# If the CALLER_GRAPH and HAVE_DOT tags are set to YES then +# doxygen will generate a caller dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable caller +# graphs for selected functions only using the \callergraph command. + +CALLER_GRAPH = NO + +# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen +# will graphical hierarchy of all classes instead of a textual one. + +GRAPHICAL_HIERARCHY = YES + +# If the DIRECTORY_GRAPH, SHOW_DIRECTORIES and HAVE_DOT tags are set to YES +# then doxygen will show the dependencies a directory has on other directories +# in a graphical way. The dependency relations are determined by the #include +# relations between the files in the directories. + +DIRECTORY_GRAPH = YES + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. Possible values are png, jpg, or gif +# If left blank png will be used. + +DOT_IMAGE_FORMAT = png + +# The tag DOT_PATH can be used to specify the path where the dot tool can be +# found. If left blank, it is assumed the dot tool can be found in the path. + +DOT_PATH = + +# The DOTFILE_DIRS tag can be used to specify one or more directories that +# contain dot files that are included in the documentation (see the +# \dotfile command). + +DOTFILE_DIRS = + +# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of +# nodes that will be shown in the graph. If the number of nodes in a graph +# becomes larger than this value, doxygen will truncate the graph, which is +# visualized by representing a node as a red box. Note that doxygen if the +# number of direct children of the root node in a graph is already larger than +# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note +# that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. + +DOT_GRAPH_MAX_NODES = 50 + +# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the +# graphs generated by dot. A depth value of 3 means that only nodes reachable +# from the root by following a path via at most 3 edges will be shown. Nodes +# that lay further from the root node will be omitted. Note that setting this +# option to 1 or 2 may greatly reduce the computation time needed for large +# code bases. Also note that the size of a graph can be further restricted by +# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. + +MAX_DOT_GRAPH_DEPTH = 0 + +# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent +# background. This is disabled by default, because dot on Windows does not +# seem to support this out of the box. Warning: Depending on the platform used, +# enabling this option may lead to badly anti-aliased labels on the edges of +# a graph (i.e. they become hard to read). + +DOT_TRANSPARENT = NO + +# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output +# files in one run (i.e. multiple -o and -T options on the command line). This +# makes dot run faster, but since only newer versions of dot (>1.8.10) +# support this, this feature is disabled by default. + +DOT_MULTI_TARGETS = YES + +# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will +# generate a legend page explaining the meaning of the various boxes and +# arrows in the dot generated graphs. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will +# remove the intermediate dot files that are used to generate +# the various graphs. + +DOT_CLEANUP = YES diff --git a/thirdParty/mavlink/doc/README b/thirdParty/mavlink/doc/README new file mode 100644 index 0000000000000000000000000000000000000000..587460140e901a588c17c4b6d821a5af8da32f24 --- /dev/null +++ b/thirdParty/mavlink/doc/README @@ -0,0 +1,9 @@ +MAVLink Micro Air Vehicle Message Marshalling Library + +The mavlink_to_html_table.xsl file is used to transform the MAVLink XML into a human-readable HTML table for online documentation. + +For more information, please visit: + +http://pixhawk.ethz.ch/software/mavlink + +(c) 2009-2010 Lorenz Meier / PIXHAWK Team diff --git a/thirdParty/mavlink/doc/mavlink.css b/thirdParty/mavlink/doc/mavlink.css new file mode 100644 index 0000000000000000000000000000000000000000..aeee8368a6ff46e6a727c9a754d4563bb9a52854 --- /dev/null +++ b/thirdParty/mavlink/doc/mavlink.css @@ -0,0 +1,54 @@ +table.sortable { + spacing: 5px; + border: 1px solid #656575; + width: 100%; +} + +table.sortable th { + margin: 5px; +} + +tr:nth-child(odd) { background-color:#eee; } +tr:nth-child(even) { background-color:#fff; } + +table.sortable thead { + background-color:#eee; + color:#666666; + font-weight: bold; + cursor: default; +} + +table.sortable td { + margin: 5px 5px 20px 5px; + vertical-align: top; +} + +table.sortable td.mavlink_name { + color:#226633; + font-weight: bold; + width: 25%; + vertical-align: top; +} + +table.sortable td.mavlink_mission_param { + color:#334455; + font-weight: bold; + width: 25%; +} + +table.sortable td.mavlink_type { + color:#323232; + font-weight: normal; + width: 12%; +} + +table.sortable td.mavlink_comment { + color:#555555; + font-weight: normal; + width: 60%; +} + +p.description { + color:#808080; + font-weight: normal; +} \ No newline at end of file diff --git a/thirdParty/mavlink/doc/mavlink.php b/thirdParty/mavlink/doc/mavlink.php new file mode 100644 index 0000000000000000000000000000000000000000..871a1306d5710353db67a9c4d1bedec55fec62e4 --- /dev/null +++ b/thirdParty/mavlink/doc/mavlink.php @@ -0,0 +1,63 @@ + + +// Requires the installation of php5-xsl +// e.g. on Debian/Ubuntu: sudo apt-get install php5-xsl + +// Load the file from the repository / server. +// Update this URL if the file location changes + +$xml_file_name = "http://github.com/pixhawk/mavlink/raw/master/mavlink_standard_message.xml"; + +// Load the XSL transformation file from the repository / server. +// This file can be updated by any client to adjust the table + +$xsl_file_name= "http://github.com/pixhawk/mavlink/raw/master/doc/mavlink_to_html_table.xsl"; + + + +// Load data XML file +$xml = file_get_contents($xml_file_name); +$xml_doc = new DomDocument; +$xml_doc->loadXML($xml); + +// Load stylesheet XSL file +$xsl = file_get_contents($xsl_file_name); +$xsl_doc = new DomDocument; +$xsl_doc->loadXML($xsl); + +$xsltproc = new XsltProcessor(); +$xsltproc->importStylesheet($xsl_doc); + +// process the files and write the output to $out_file +if ($html = $xsltproc->transformToXML($xml_doc)) +{ + echo $html; +} +else +{ + trigger_error('XSL transformation failed.',E_USER_ERROR); +} + + + + +

Messages XML Definition

+ +Messages are defined by the mavlink_standard_message.xml file. The C packing/unpacking code is generated from this specification, as well as the HTML documentaiton in the section above.
+
+The XML displayed here is updated on every commit and therefore up-to-date. + + +//require_once("inc/geshi.php"); +//$xml_file_name = "http://github.com/pixhawk/mavlink/raw/master/mavlink_standard_message.xml"; +// +//// Load data XML file +//$xml = file_get_contents($xml_file_name); +// +//// Show the current code +//$geshi_xml = new GeSHi($xml, 'xml'); +//$display_xml = $geshi_xml->parse_code(); +// +//echo $display_xml; + + \ No newline at end of file diff --git a/thirdParty/mavlink/doc/mavlink_to_html_table.xsl b/thirdParty/mavlink/doc/mavlink_to_html_table.xsl new file mode 100644 index 0000000000000000000000000000000000000000..1b1d9461ae42cdaa581998fe226e3eaeba09d16f --- /dev/null +++ b/thirdParty/mavlink/doc/mavlink_to_html_table.xsl @@ -0,0 +1,93 @@ + + + + + +

MAVLink Include Files

+

Including files:

+
+ + +

MAVLink Type Enumerations

+ +
+ + +

MAVLink Messages

+ +
+ + + +

+ + + + + + + + + + + + +
Field NameTypeDescription
+
+ + + + + + + + + + +

MAVLink Protocol Version

+

This file has protocol version: . The version numbers range from 1-255.

+
+ + + +

+ + + + + + + + + + + + +
CMD IDField NameDescription
+
+ + + + + + + + + + + + +
+ +
+ + + + + Mission Param # + + + + + +
diff --git a/thirdParty/mavlink/include/ardupilotmega/ardupilotmega.h b/thirdParty/mavlink/include/ardupilotmega/ardupilotmega.h new file mode 100644 index 0000000000000000000000000000000000000000..98139a642702d55b6d8fc1756806e32dd967d9ab --- /dev/null +++ b/thirdParty/mavlink/include/ardupilotmega/ardupilotmega.h @@ -0,0 +1,39 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Thursday, March 31 2011, 22:06 UTC + */ +#ifndef ARDUPILOTMEGA_H +#define ARDUPILOTMEGA_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "../protocol.h" + +#define MAVLINK_ENABLED_ARDUPILOTMEGA + + +#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 + + +// MESSAGE DEFINITIONS + +#ifdef __cplusplus +} +#endif +#endif diff --git a/thirdParty/mavlink/include/ardupilotmega/mavlink.h b/thirdParty/mavlink/include/ardupilotmega/mavlink.h new file mode 100644 index 0000000000000000000000000000000000000000..1e2a10442fe3e384b3a8cc53fe26356055709e92 --- /dev/null +++ b/thirdParty/mavlink/include/ardupilotmega/mavlink.h @@ -0,0 +1,11 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Thursday, March 31 2011, 22:06 UTC + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#include "ardupilotmega.h" + +#endif diff --git a/thirdParty/mavlink/include/bittest.c b/thirdParty/mavlink/include/bittest.c new file mode 100644 index 0000000000000000000000000000000000000000..c966b72afb7676ca72721366f4bcfb9329ffbb4b --- /dev/null +++ b/thirdParty/mavlink/include/bittest.c @@ -0,0 +1,39 @@ +#include +#include + +int main(int argc, char* argv[]) +{ + + uint8_t bitfield = 254; // 11111110 + + uint8_t mask = 128; // 10000000 + + uint8_t result = (bitfield & mask); + + printf("0x%02x\n", bitfield); + + // Transform into network order + + generic_32bit bin; + bin.i = 1; + printf("First byte in (little endian) 0x%02x\n", bin.b[0]); + generic_32bit bout; + bout.b[0] = bin.b[3]; + bout.b[1] = bin.b[2]; + bout.b[2] = bin.b[1]; + bout.b[3] = bin.b[0]; + printf("Last byte out (big endian) 0x%02x\n", bout.b[3]); + + uint8_t n = 5; + printf("Mask is 0x%02x\n", ((uint32_t)(1 << n)) - 1); // = 2^n - 1 + + int32_t encoded = 2; + uint8_t bits = 2; + + uint8_t packet[MAVLINK_MAX_PACKET_LEN]; + uint8_t packet_index = 0; + uint8_t bit_index = 0; + + put_bitfield_n_by_index(encoded, bits, packet_index, bit_index, &bit_index, packet); + +} diff --git a/thirdParty/mavlink/include/checksum.h b/thirdParty/mavlink/include/checksum.h new file mode 100644 index 0000000000000000000000000000000000000000..c16a06e1b9c6430af8ec637ec04e6d221ee38067 --- /dev/null +++ b/thirdParty/mavlink/include/checksum.h @@ -0,0 +1,95 @@ +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef _CHECKSUM_H_ +#define _CHECKSUM_H_ + +#include "inttypes.h" + + +/** + * + * CALCULATE THE CHECKSUM + * + */ + +#define X25_INIT_CRC 0xffff +#define X25_VALIDATE_CRC 0xf0b8 + +/** + * @brief Accumulate the X.25 CRC by adding one char at a time. + * + * The checksum function adds the hash of one char at a time to the + * 16 bit checksum (uint16_t). + * + * @param data new char to hash + * @param crcAccum the already accumulated checksum + **/ +static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) +{ + /*Accumulate one byte of data into the CRC*/ + uint8_t tmp; + + tmp=data ^ (uint8_t)(*crcAccum &0xff); + tmp^= (tmp<<4); + *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); +} + +/** + * @brief Initiliaze the buffer for the X.25 CRC + * + * @param crcAccum the 16 bit X.25 CRC + */ +static inline void crc_init(uint16_t* crcAccum) +{ + *crcAccum = X25_INIT_CRC; +} + + +/** + * @brief Calculates the X.25 checksum on a byte buffer + * + * @param pBuffer buffer containing the byte array to hash + * @param length length of the byte array + * @return the checksum over the buffer bytes + **/ +static inline uint16_t crc_calculate(uint8_t* pBuffer, int length) +{ + + // For a "message" of length bytes contained in the unsigned char array + // pointed to by pBuffer, calculate the CRC + // crcCalculate(unsigned char* pBuffer, int length, unsigned short* checkConst) < not needed + + uint16_t crcTmp; + //uint16_t tmp; + uint8_t* pTmp; + int i; + + pTmp=pBuffer; + + + /* init crcTmp */ + crc_init(&crcTmp); + + for (i = 0; i < length; i++){ + crc_accumulate(*pTmp++, &crcTmp); + } + + /* This is currently not needed, as only the checksum over payload should be computed + tmp = crcTmp; + crcAccumulate((unsigned char)(~crcTmp & 0xff),&tmp); + crcAccumulate((unsigned char)((~crcTmp>>8)&0xff),&tmp); + *checkConst = tmp; + */ + return(crcTmp); +} + + + + +#endif /* _CHECKSUM_H_ */ + +#ifdef __cplusplus +} +#endif diff --git a/thirdParty/mavlink/include/common/common.h b/thirdParty/mavlink/include/common/common.h new file mode 100644 index 0000000000000000000000000000000000000000..df1f685d91d1c2d92c4c671f9b5b8232bec4240f --- /dev/null +++ b/thirdParty/mavlink/include/common/common.h @@ -0,0 +1,149 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Thursday, March 31 2011, 22:06 UTC + */ +#ifndef COMMON_H +#define COMMON_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "../protocol.h" + +#define MAVLINK_ENABLED_COMMON + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// ENUM DEFINITIONS + +/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ +enum MAV_CMD +{ + MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint.Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached)0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.Desired yaw angle at waypoint (rotary wing)LatitudeLongitudeAltitude*/ + MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of timeEmptyEmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/ + MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turnsTurnsEmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/ + MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this waypoint for X secondsSeconds (decimal)EmptyRadius around waypoint, in meters. If positive loiter clockwise, else counter-clockwiseDesired yaw angle.LatitudeLongitudeAltitude*/ + MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch locationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/ + MAV_CMD_NAV_LAND=21, /* Land at locationEmptyEmptyEmptyDesired yaw angle.LatitudeLongitudeAltitude*/ + MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / handMinimum pitch (if airspeed sensor present), desired pitch without sensorEmptyEmptyYaw angle (if magnetometer present), ignored without magnetometerLatitudeLongitudeAltitude*/ + MAV_CMD_NAV_ORIENTATION_TARGET=80, /* Set the location the system should be heading towards (camera heads or rotary wing aircraft).EmptyEmptyEmptyEmptyLatitudeLongitudeAltitude*/ + MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV.0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy gridEmptyYaw angle at goal, in compass degrees, [0..360]Latitude/X of goalLongitude/Y of goalAltitude/Z of goal*/ + MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/ + MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine.Delay in seconds (decimal)EmptyEmptyEmptyEmptyEmptyEmpty*/ + MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached.Descent / Ascend rate (m/s)EmptyEmptyEmptyEmptyEmptyFinish Altitude*/ + MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point.Distance (meters)EmptyEmptyEmptyEmptyEmptyEmpty*/ + MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle.target angle: [0-360], 0 is northspeed during yaw change:[deg per second]direction: negative: counter clockwise, positive: clockwise [-1,1]relative offset or absolute angle: [ 1,0]EmptyEmptyEmpty*/ + MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/ + MAV_CMD_DO_SET_MODE=176, /* Set system mode.Mode, as defined by ENUM MAV_MODEEmptyEmptyEmptyEmptyEmptyEmpty*/ + MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of timesSequence numberRepeat countEmptyEmptyEmptyEmptyEmpty*/ + MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points.Speed type (0=Airspeed, 1=Ground Speed)Speed (m/s, -1 indicates no change)Throttle ( Percent, -1 indicates no change)EmptyEmptyEmptyEmpty*/ + MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location.Use current (1=use current location, 0=use specified location)EmptyEmptyEmptyLatitudeLongitudeAltitude*/ + MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.Parameter numberParameter valueEmptyEmptyEmptyEmptyEmpty*/ + MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition.Relay numberSetting (1=on, 0=off, others possible depending on system hardware)EmptyEmptyEmptyEmptyEmpty*/ + MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period.Relay numberCycle countCycle time (seconds, decimal)EmptyEmptyEmptyEmpty*/ + MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value.Servo numberPWM (microseconds, 1000 to 2000 typical)EmptyEmptyEmptyEmptyEmpty*/ + MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.Servo numberPWM (microseconds, 1000 to 2000 typical)Cycle countCycle time (seconds)EmptyEmptyEmpty*/ + MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system.Camera ID (-1 for all)Transmission: 0: disabled, 1: enabled compressed, 2: enabled rawTransmission mode: 0: video stream, >0: single images every n seconds (decimal)Recording: 0: disabled, 1: enabled compressed, 2: enabled rawEmptyEmptyEmpty*/ + MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/ + MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode.Gyro calibration: 0: no, 1: yesMagnetometer calibration: 0: no, 1: yesGround pressure: 0: no, 1: yesRadio calibration: 0: no, 1: yesEmptyEmptyEmpty*/ + MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROMMission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROMReservedReservedEmptyEmptyEmpty*/ + MAV_CMD_ENUM_END +}; + +/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages. */ +enum MAV_DATA_STREAM +{ + MAV_DATA_STREAM_ALL=0, /* Enable all data streams*/ + MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.*/ + MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS*/ + MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW*/ + MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.*/ + MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.*/ + MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot*/ + MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot*/ + MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot*/ + MAV_DATA_STREAM_ENUM_END +}; + + +// MESSAGE DEFINITIONS + +#include "./mavlink_msg_heartbeat.h" +#include "./mavlink_msg_boot.h" +#include "./mavlink_msg_system_time.h" +#include "./mavlink_msg_ping.h" +#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" +#include "./mavlink_msg_set_nav_mode.h" +#include "./mavlink_msg_param_request_read.h" +#include "./mavlink_msg_param_request_list.h" +#include "./mavlink_msg_param_value.h" +#include "./mavlink_msg_param_set.h" +#include "./mavlink_msg_gps_raw_int.h" +#include "./mavlink_msg_scaled_imu.h" +#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" +#include "./mavlink_msg_gps_raw.h" +#include "./mavlink_msg_sys_status.h" +#include "./mavlink_msg_rc_channels_raw.h" +#include "./mavlink_msg_rc_channels_scaled.h" +#include "./mavlink_msg_servo_output_raw.h" +#include "./mavlink_msg_waypoint.h" +#include "./mavlink_msg_waypoint_request.h" +#include "./mavlink_msg_waypoint_set_current.h" +#include "./mavlink_msg_waypoint_current.h" +#include "./mavlink_msg_waypoint_request_list.h" +#include "./mavlink_msg_waypoint_count.h" +#include "./mavlink_msg_waypoint_clear_all.h" +#include "./mavlink_msg_waypoint_reached.h" +#include "./mavlink_msg_waypoint_ack.h" +#include "./mavlink_msg_gps_set_global_origin.h" +#include "./mavlink_msg_gps_local_origin_set.h" +#include "./mavlink_msg_local_position_setpoint_set.h" +#include "./mavlink_msg_local_position_setpoint.h" +#include "./mavlink_msg_control_status.h" +#include "./mavlink_msg_safety_set_allowed_area.h" +#include "./mavlink_msg_safety_allowed_area.h" +#include "./mavlink_msg_attitude_controller_output.h" +#include "./mavlink_msg_position_controller_output.h" +#include "./mavlink_msg_nav_controller_output.h" +#include "./mavlink_msg_position_target.h" +#include "./mavlink_msg_state_correction.h" +#include "./mavlink_msg_set_altitude.h" +#include "./mavlink_msg_request_data_stream.h" +#include "./mavlink_msg_manual_control.h" +#include "./mavlink_msg_global_position_int.h" +#include "./mavlink_msg_vfr_hud.h" +#include "./mavlink_msg_command.h" +#include "./mavlink_msg_command_ack.h" +#include "./mavlink_msg_debug_vect.h" +#include "./mavlink_msg_named_value_float.h" +#include "./mavlink_msg_named_value_int.h" +#include "./mavlink_msg_statustext.h" +#include "./mavlink_msg_debug.h" +#ifdef __cplusplus +} +#endif +#endif diff --git a/thirdParty/mavlink/include/common/mavlink.h b/thirdParty/mavlink/include/common/mavlink.h new file mode 100644 index 0000000000000000000000000000000000000000..fc3473e9f6d6bbde6271f602540651905a6fc23a --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink.h @@ -0,0 +1,11 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Thursday, March 31 2011, 22:06 UTC + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#include "common.h" + +#endif diff --git a/thirdParty/mavlink/include/common/mavlink_msg_action.h b/thirdParty/mavlink/include/common/mavlink_msg_action.h new file mode 100644 index 0000000000000000000000000000000000000000..f1de5467547fff8b3c40f00f9da082ed6f54477a --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_action.h @@ -0,0 +1,135 @@ +// MESSAGE ACTION PACKING + +#define MAVLINK_MSG_ID_ACTION 10 + +typedef struct __mavlink_action_t +{ + uint8_t target; ///< The system executing the action + uint8_t target_component; ///< The component executing the action + uint8_t action; ///< The action id + +} mavlink_action_t; + + + +/** + * @brief Pack a 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 executing the action + * @param target_component The component executing the action + * @param action The action id + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_action_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t target_component, uint8_t action) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ACTION; + + i += put_uint8_t_by_index(target, i, msg->payload); // The system executing the action + i += put_uint8_t_by_index(target_component, i, msg->payload); // The component executing the action + i += put_uint8_t_by_index(action, i, msg->payload); // The action id + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a 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 executing the action + * @param target_component The component executing the action + * @param action The action id + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_action_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t target_component, uint8_t action) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ACTION; + + i += put_uint8_t_by_index(target, i, msg->payload); // The system executing the action + i += put_uint8_t_by_index(target_component, i, msg->payload); // The component executing the action + i += put_uint8_t_by_index(action, i, msg->payload); // The action id + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a 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 action C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_action_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_t* action) +{ + return mavlink_msg_action_pack(system_id, component_id, msg, action->target, action->target_component, action->action); +} + +/** + * @brief Send a action message + * @param chan MAVLink channel to send the message + * + * @param target The system executing the action + * @param target_component The component executing the action + * @param action The action id + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_action_send(mavlink_channel_t chan, uint8_t target, uint8_t target_component, uint8_t action) +{ + mavlink_message_t msg; + mavlink_msg_action_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, target_component, action); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE ACTION UNPACKING + +/** + * @brief Get field target from action message + * + * @return The system executing the action + */ +static inline uint8_t mavlink_msg_action_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from action message + * + * @return The component executing the action + */ +static inline uint8_t mavlink_msg_action_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field action from action message + * + * @return The action id + */ +static inline uint8_t mavlink_msg_action_get_action(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a action message into a struct + * + * @param msg The message to decode + * @param action C-struct to decode the message contents into + */ +static inline void mavlink_msg_action_decode(const mavlink_message_t* msg, mavlink_action_t* action) +{ + action->target = mavlink_msg_action_get_target(msg); + action->target_component = mavlink_msg_action_get_target_component(msg); + action->action = mavlink_msg_action_get_action(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_action_ack.h b/thirdParty/mavlink/include/common/mavlink_msg_action_ack.h new file mode 100644 index 0000000000000000000000000000000000000000..6e93449e205003bd383a123cb938e7ad645fd031 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_action_ack.h @@ -0,0 +1,118 @@ +// MESSAGE ACTION_ACK PACKING + +#define MAVLINK_MSG_ID_ACTION_ACK 9 + +typedef struct __mavlink_action_ack_t +{ + uint8_t action; ///< The action id + uint8_t result; ///< 0: Action DENIED, 1: Action executed + +} mavlink_action_ack_t; + + + +/** + * @brief Pack a action_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param action The action id + * @param result 0: Action DENIED, 1: Action executed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_action_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t action, uint8_t result) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ACTION_ACK; + + i += put_uint8_t_by_index(action, i, msg->payload); // The action id + i += put_uint8_t_by_index(result, i, msg->payload); // 0: Action DENIED, 1: Action executed + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a action_ack 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 action The action id + * @param result 0: Action DENIED, 1: Action executed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_action_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t action, uint8_t result) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ACTION_ACK; + + i += put_uint8_t_by_index(action, i, msg->payload); // The action id + i += put_uint8_t_by_index(result, i, msg->payload); // 0: Action DENIED, 1: Action executed + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a action_ack 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 action_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_action_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_ack_t* action_ack) +{ + return mavlink_msg_action_ack_pack(system_id, component_id, msg, action_ack->action, action_ack->result); +} + +/** + * @brief Send a action_ack message + * @param chan MAVLink channel to send the message + * + * @param action The action id + * @param result 0: Action DENIED, 1: Action executed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_action_ack_send(mavlink_channel_t chan, uint8_t action, uint8_t result) +{ + mavlink_message_t msg; + mavlink_msg_action_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, action, result); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE ACTION_ACK UNPACKING + +/** + * @brief Get field action from action_ack message + * + * @return The action id + */ +static inline uint8_t mavlink_msg_action_ack_get_action(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field result from action_ack message + * + * @return 0: Action DENIED, 1: Action executed + */ +static inline uint8_t mavlink_msg_action_ack_get_result(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a action_ack message into a struct + * + * @param msg The message to decode + * @param action_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_action_ack_decode(const mavlink_message_t* msg, mavlink_action_ack_t* action_ack) +{ + action_ack->action = mavlink_msg_action_ack_get_action(msg); + action_ack->result = mavlink_msg_action_ack_get_result(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_attitude.h b/thirdParty/mavlink/include/common/mavlink_msg_attitude.h new file mode 100644 index 0000000000000000000000000000000000000000..6daba3c54b2a8806210871091cfdff74f55808ee --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_attitude.h @@ -0,0 +1,242 @@ +// MESSAGE ATTITUDE PACKING + +#define MAVLINK_MSG_ID_ATTITUDE 30 + +typedef struct __mavlink_attitude_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + float roll; ///< Roll angle (rad) + float pitch; ///< Pitch angle (rad) + float yaw; ///< Yaw angle (rad) + float rollspeed; ///< Roll angular speed (rad/s) + float pitchspeed; ///< Pitch angular speed (rad/s) + float yawspeed; ///< Yaw angular speed (rad/s) + +} mavlink_attitude_t; + + + +/** + * @brief Pack a attitude message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ATTITUDE; + + 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(roll, i, msg->payload); // Roll angle (rad) + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad) + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad) + i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s) + i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s) + i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a attitude message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param 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 roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ATTITUDE; + + 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(roll, i, msg->payload); // Roll angle (rad) + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad) + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad) + i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s) + i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s) + i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s) + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a attitude 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 attitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude) +{ + return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->usec, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); +} + +/** + * @brief Send a attitude message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ + mavlink_message_t msg; + mavlink_msg_attitude_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE ATTITUDE UNPACKING + +/** + * @brief Get field usec from attitude message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_attitude_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field roll from attitude message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_attitude_get_roll(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; +} + +/** + * @brief Get field pitch from attitude message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_attitude_get_pitch(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; +} + +/** + * @brief Get field yaw from attitude message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_attitude_get_yaw(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; +} + +/** + * @brief Get field rollspeed from attitude message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitchspeed from attitude message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yawspeed from attitude message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a attitude message into a struct + * + * @param msg The message to decode + * @param attitude C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude) +{ + attitude->usec = mavlink_msg_attitude_get_usec(msg); + attitude->roll = mavlink_msg_attitude_get_roll(msg); + attitude->pitch = mavlink_msg_attitude_get_pitch(msg); + attitude->yaw = mavlink_msg_attitude_get_yaw(msg); + attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg); + attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); + attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_attitude_controller_output.h b/thirdParty/mavlink/include/common/mavlink_msg_attitude_controller_output.h new file mode 100644 index 0000000000000000000000000000000000000000..60fa775540642cfd8eb876fd33163edb75ab4946 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_attitude_controller_output.h @@ -0,0 +1,169 @@ +// MESSAGE ATTITUDE_CONTROLLER_OUTPUT PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT 60 + +typedef struct __mavlink_attitude_controller_output_t +{ + uint8_t enabled; ///< 1: enabled, 0: disabled + int8_t roll; ///< Attitude roll: -128: -100%, 127: +100% + int8_t pitch; ///< Attitude pitch: -128: -100%, 127: +100% + int8_t yaw; ///< Attitude yaw: -128: -100%, 127: +100% + int8_t thrust; ///< Attitude thrust: -128: -100%, 127: +100% + +} mavlink_attitude_controller_output_t; + + + +/** + * @brief Pack a attitude_controller_output 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 enabled 1: enabled, 0: disabled + * @param roll Attitude roll: -128: -100%, 127: +100% + * @param pitch Attitude pitch: -128: -100%, 127: +100% + * @param yaw Attitude yaw: -128: -100%, 127: +100% + * @param thrust Attitude thrust: -128: -100%, 127: +100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t enabled, int8_t roll, int8_t pitch, int8_t yaw, int8_t thrust) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT; + + i += put_uint8_t_by_index(enabled, i, msg->payload); // 1: enabled, 0: disabled + i += put_int8_t_by_index(roll, i, msg->payload); // Attitude roll: -128: -100%, 127: +100% + i += put_int8_t_by_index(pitch, i, msg->payload); // Attitude pitch: -128: -100%, 127: +100% + i += put_int8_t_by_index(yaw, i, msg->payload); // Attitude yaw: -128: -100%, 127: +100% + i += put_int8_t_by_index(thrust, i, msg->payload); // Attitude thrust: -128: -100%, 127: +100% + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a attitude_controller_output 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 enabled 1: enabled, 0: disabled + * @param roll Attitude roll: -128: -100%, 127: +100% + * @param pitch Attitude pitch: -128: -100%, 127: +100% + * @param yaw Attitude yaw: -128: -100%, 127: +100% + * @param thrust Attitude thrust: -128: -100%, 127: +100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enabled, int8_t roll, int8_t pitch, int8_t yaw, int8_t thrust) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT; + + i += put_uint8_t_by_index(enabled, i, msg->payload); // 1: enabled, 0: disabled + i += put_int8_t_by_index(roll, i, msg->payload); // Attitude roll: -128: -100%, 127: +100% + i += put_int8_t_by_index(pitch, i, msg->payload); // Attitude pitch: -128: -100%, 127: +100% + i += put_int8_t_by_index(yaw, i, msg->payload); // Attitude yaw: -128: -100%, 127: +100% + i += put_int8_t_by_index(thrust, i, msg->payload); // Attitude thrust: -128: -100%, 127: +100% + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a attitude_controller_output 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 attitude_controller_output C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_controller_output_t* attitude_controller_output) +{ + return mavlink_msg_attitude_controller_output_pack(system_id, component_id, msg, attitude_controller_output->enabled, attitude_controller_output->roll, attitude_controller_output->pitch, attitude_controller_output->yaw, attitude_controller_output->thrust); +} + +/** + * @brief Send a attitude_controller_output message + * @param chan MAVLink channel to send the message + * + * @param enabled 1: enabled, 0: disabled + * @param roll Attitude roll: -128: -100%, 127: +100% + * @param pitch Attitude pitch: -128: -100%, 127: +100% + * @param yaw Attitude yaw: -128: -100%, 127: +100% + * @param thrust Attitude thrust: -128: -100%, 127: +100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_controller_output_send(mavlink_channel_t chan, uint8_t enabled, int8_t roll, int8_t pitch, int8_t yaw, int8_t thrust) +{ + mavlink_message_t msg; + mavlink_msg_attitude_controller_output_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, enabled, roll, pitch, yaw, thrust); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE ATTITUDE_CONTROLLER_OUTPUT UNPACKING + +/** + * @brief Get field enabled from attitude_controller_output message + * + * @return 1: enabled, 0: disabled + */ +static inline uint8_t mavlink_msg_attitude_controller_output_get_enabled(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field roll from attitude_controller_output message + * + * @return Attitude roll: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_attitude_controller_output_get_roll(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field pitch from attitude_controller_output message + * + * @return Attitude pitch: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_attitude_controller_output_get_pitch(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t))[0]; +} + +/** + * @brief Get field yaw from attitude_controller_output message + * + * @return Attitude yaw: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_attitude_controller_output_get_yaw(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t)+sizeof(int8_t))[0]; +} + +/** + * @brief Get field thrust from attitude_controller_output message + * + * @return Attitude thrust: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_attitude_controller_output_get_thrust(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t)+sizeof(int8_t)+sizeof(int8_t))[0]; +} + +/** + * @brief Decode a attitude_controller_output message into a struct + * + * @param msg The message to decode + * @param attitude_controller_output C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_controller_output_decode(const mavlink_message_t* msg, mavlink_attitude_controller_output_t* attitude_controller_output) +{ + attitude_controller_output->enabled = mavlink_msg_attitude_controller_output_get_enabled(msg); + attitude_controller_output->roll = mavlink_msg_attitude_controller_output_get_roll(msg); + attitude_controller_output->pitch = mavlink_msg_attitude_controller_output_get_pitch(msg); + attitude_controller_output->yaw = mavlink_msg_attitude_controller_output_get_yaw(msg); + attitude_controller_output->thrust = mavlink_msg_attitude_controller_output_get_thrust(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_auth_key.h b/thirdParty/mavlink/include/common/mavlink_msg_auth_key.h new file mode 100644 index 0000000000000000000000000000000000000000..605ba7db61bbd6ef3a93d1b338edd1121789eb45 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_auth_key.h @@ -0,0 +1,104 @@ +// MESSAGE AUTH_KEY PACKING + +#define MAVLINK_MSG_ID_AUTH_KEY 7 + +typedef struct __mavlink_auth_key_t +{ + char key[32]; ///< key + +} mavlink_auth_key_t; + +#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32 + + +/** + * @brief Pack a auth_key message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param key key + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* key) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; + + i += put_array_by_index((const int8_t*)key, sizeof(char)*32, i, msg->payload); // key + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a auth_key message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param key key + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* key) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; + + i += put_array_by_index((const int8_t*)key, sizeof(char)*32, i, msg->payload); // key + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a auth_key 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 auth_key C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) +{ + return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key); +} + +/** + * @brief Send a auth_key message + * @param chan MAVLink channel to send the message + * + * @param key key + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char* key) +{ + mavlink_message_t msg; + mavlink_msg_auth_key_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, key); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE AUTH_KEY UNPACKING + +/** + * @brief Get field key from auth_key message + * + * @return key + */ +static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char* r_data) +{ + + memcpy(r_data, msg->payload, sizeof(char)*32); + return sizeof(char)*32; +} + +/** + * @brief Decode a auth_key message into a struct + * + * @param msg The message to decode + * @param auth_key C-struct to decode the message contents into + */ +static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key) +{ + mavlink_msg_auth_key_get_key(msg, auth_key->key); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_boot.h b/thirdParty/mavlink/include/common/mavlink_msg_boot.h new file mode 100644 index 0000000000000000000000000000000000000000..69d8ed64a7d91095e4637d5153dc964857ec9151 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_boot.h @@ -0,0 +1,106 @@ +// MESSAGE BOOT PACKING + +#define MAVLINK_MSG_ID_BOOT 1 + +typedef struct __mavlink_boot_t +{ + uint32_t version; ///< The onboard software version + +} mavlink_boot_t; + + + +/** + * @brief Pack a boot 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 version The onboard software version + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t version) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_BOOT; + + i += put_uint32_t_by_index(version, i, msg->payload); // The onboard software version + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a boot 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 version The onboard software version + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_boot_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t version) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_BOOT; + + i += put_uint32_t_by_index(version, i, msg->payload); // The onboard software version + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a boot 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 boot C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_boot_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_boot_t* boot) +{ + return mavlink_msg_boot_pack(system_id, component_id, msg, boot->version); +} + +/** + * @brief Send a boot message + * @param chan MAVLink channel to send the message + * + * @param version The onboard software version + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_boot_send(mavlink_channel_t chan, uint32_t version) +{ + mavlink_message_t msg; + mavlink_msg_boot_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, version); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE BOOT UNPACKING + +/** + * @brief Get field version from boot message + * + * @return The onboard software version + */ +static inline uint32_t mavlink_msg_boot_get_version(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 (uint32_t)r.i; +} + +/** + * @brief Decode a boot message into a struct + * + * @param msg The message to decode + * @param boot C-struct to decode the message contents into + */ +static inline void mavlink_msg_boot_decode(const mavlink_message_t* msg, mavlink_boot_t* boot) +{ + boot->version = mavlink_msg_boot_get_version(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_change_operator_control.h b/thirdParty/mavlink/include/common/mavlink_msg_change_operator_control.h new file mode 100644 index 0000000000000000000000000000000000000000..3eab478cbf84010a62c3b8f3b3195a1918ebd4b4 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_change_operator_control.h @@ -0,0 +1,155 @@ +// MESSAGE CHANGE_OPERATOR_CONTROL PACKING + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 + +typedef struct __mavlink_change_operator_control_t +{ + uint8_t target_system; ///< System the GCS requests control for + uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV + uint8_t version; ///< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + char passkey[25]; ///< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + +} mavlink_change_operator_control_t; + +#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25 + + +/** + * @brief Pack a change_operator_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t control_request, uint8_t version, const char* passkey) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; + + i += put_uint8_t_by_index(target_system, i, msg->payload); // System the GCS requests control for + i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV + i += put_uint8_t_by_index(version, i, msg->payload); // 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + i += put_array_by_index((const int8_t*)passkey, sizeof(char)*25, i, msg->payload); // Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a change_operator_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t control_request, uint8_t version, const char* passkey) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; + + i += put_uint8_t_by_index(target_system, i, msg->payload); // System the GCS requests control for + i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV + i += put_uint8_t_by_index(version, i, msg->payload); // 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + i += put_array_by_index((const int8_t*)passkey, sizeof(char)*25, i, msg->payload); // Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a change_operator_control 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 change_operator_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) +{ + return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); +} + +/** + * @brief Send a change_operator_control message + * @param chan MAVLink channel to send the message + * + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char* passkey) +{ + mavlink_message_t msg; + mavlink_msg_change_operator_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, control_request, version, passkey); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING + +/** + * @brief Get field target_system from change_operator_control message + * + * @return System the GCS requests control for + */ +static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field control_request from change_operator_control message + * + * @return 0: request control of this MAV, 1: Release control of this MAV + */ +static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field version from change_operator_control message + * + * @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + */ +static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field passkey from change_operator_control message + * + * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + */ +static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t), sizeof(char)*25); + return sizeof(char)*25; +} + +/** + * @brief Decode a change_operator_control message into a struct + * + * @param msg The message to decode + * @param change_operator_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control) +{ + change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg); + change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg); + change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg); + mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_change_operator_control_ack.h b/thirdParty/mavlink/include/common/mavlink_msg_change_operator_control_ack.h new file mode 100644 index 0000000000000000000000000000000000000000..3529ae059119053772ca0024d6d7195a1b371eec --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_change_operator_control_ack.h @@ -0,0 +1,135 @@ +// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 + +typedef struct __mavlink_change_operator_control_ack_t +{ + uint8_t gcs_system_id; ///< ID of the GCS this message + uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV + uint8_t ack; ///< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + +} mavlink_change_operator_control_ack_t; + + + +/** + * @brief Pack a change_operator_control_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; + + i += put_uint8_t_by_index(gcs_system_id, i, msg->payload); // ID of the GCS this message + i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV + i += put_uint8_t_by_index(ack, i, msg->payload); // 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a change_operator_control_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; + + i += put_uint8_t_by_index(gcs_system_id, i, msg->payload); // ID of the GCS this message + i += put_uint8_t_by_index(control_request, i, msg->payload); // 0: request control of this MAV, 1: Release control of this MAV + i += put_uint8_t_by_index(ack, i, msg->payload); // 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a change_operator_control_ack 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 change_operator_control_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ + return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); +} + +/** + * @brief Send a change_operator_control_ack message + * @param chan MAVLink channel to send the message + * + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ + mavlink_message_t msg; + mavlink_msg_change_operator_control_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, gcs_system_id, control_request, ack); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING + +/** + * @brief Get field gcs_system_id from change_operator_control_ack message + * + * @return ID of the GCS this message + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field control_request from change_operator_control_ack message + * + * @return 0: request control of this MAV, 1: Release control of this MAV + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field ack from change_operator_control_ack message + * + * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a change_operator_control_ack message into a struct + * + * @param msg The message to decode + * @param change_operator_control_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ + change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg); + change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg); + change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_command.h b/thirdParty/mavlink/include/common/mavlink_msg_command.h new file mode 100644 index 0000000000000000000000000000000000000000..dbc123570730ed4501bea2114ff93835eee68797 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_command.h @@ -0,0 +1,240 @@ +// MESSAGE COMMAND PACKING + +#define MAVLINK_MSG_ID_COMMAND 75 + +typedef struct __mavlink_command_t +{ + uint8_t target_system; ///< System which should execute the command + uint8_t target_component; ///< Component which should execute the command, 0 for all components + uint8_t command; ///< Command ID, as defined by MAV_CMD enum. + uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + float param1; ///< Parameter 1, as defined by MAV_CMD enum. + float param2; ///< Parameter 2, as defined by MAV_CMD enum. + float param3; ///< Parameter 3, as defined by MAV_CMD enum. + float param4; ///< Parameter 4, as defined by MAV_CMD enum. + +} mavlink_command_t; + + + +/** + * @brief Pack a command message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_COMMAND; + + i += put_uint8_t_by_index(target_system, i, msg->payload); // System which should execute the command + i += put_uint8_t_by_index(target_component, i, msg->payload); // Component which should execute the command, 0 for all components + i += put_uint8_t_by_index(command, i, msg->payload); // Command ID, as defined by MAV_CMD enum. + i += put_uint8_t_by_index(confirmation, i, msg->payload); // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + i += put_float_by_index(param1, i, msg->payload); // Parameter 1, as defined by MAV_CMD enum. + i += put_float_by_index(param2, i, msg->payload); // Parameter 2, as defined by MAV_CMD enum. + i += put_float_by_index(param3, i, msg->payload); // Parameter 3, as defined by MAV_CMD enum. + i += put_float_by_index(param4, i, msg->payload); // Parameter 4, as defined by MAV_CMD enum. + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a command 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 System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_COMMAND; + + i += put_uint8_t_by_index(target_system, i, msg->payload); // System which should execute the command + i += put_uint8_t_by_index(target_component, i, msg->payload); // Component which should execute the command, 0 for all components + i += put_uint8_t_by_index(command, i, msg->payload); // Command ID, as defined by MAV_CMD enum. + i += put_uint8_t_by_index(confirmation, i, msg->payload); // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + i += put_float_by_index(param1, i, msg->payload); // Parameter 1, as defined by MAV_CMD enum. + i += put_float_by_index(param2, i, msg->payload); // Parameter 2, as defined by MAV_CMD enum. + i += put_float_by_index(param3, i, msg->payload); // Parameter 3, as defined by MAV_CMD enum. + i += put_float_by_index(param4, i, msg->payload); // Parameter 4, as defined by MAV_CMD enum. + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a command 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 command C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_t* command) +{ + return mavlink_msg_command_pack(system_id, component_id, msg, command->target_system, command->target_component, command->command, command->confirmation, command->param1, command->param2, command->param3, command->param4); +} + +/** + * @brief Send a command message + * @param chan MAVLink channel to send the message + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4) +{ + mavlink_message_t msg; + mavlink_msg_command_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, command, confirmation, param1, param2, param3, param4); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE COMMAND UNPACKING + +/** + * @brief Get field target_system from command message + * + * @return System which should execute the command + */ +static inline uint8_t mavlink_msg_command_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from command message + * + * @return Component which should execute the command, 0 for all components + */ +static inline uint8_t mavlink_msg_command_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field command from command message + * + * @return Command ID, as defined by MAV_CMD enum. + */ +static inline uint8_t mavlink_msg_command_get_command(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field confirmation from command message + * + * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + */ +static inline uint8_t mavlink_msg_command_get_confirmation(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field param1 from command message + * + * @return Parameter 1, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_get_param1(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field param2 from command message + * + * @return Parameter 2, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_get_param2(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field param3 from command message + * + * @return Parameter 3, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_get_param3(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field param4 from command message + * + * @return Parameter 4, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_get_param4(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a command message into a struct + * + * @param msg The message to decode + * @param command C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_decode(const mavlink_message_t* msg, mavlink_command_t* command) +{ + command->target_system = mavlink_msg_command_get_target_system(msg); + command->target_component = mavlink_msg_command_get_target_component(msg); + command->command = mavlink_msg_command_get_command(msg); + command->confirmation = mavlink_msg_command_get_confirmation(msg); + command->param1 = mavlink_msg_command_get_param1(msg); + command->param2 = mavlink_msg_command_get_param2(msg); + command->param3 = mavlink_msg_command_get_param3(msg); + command->param4 = mavlink_msg_command_get_param4(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_command_ack.h b/thirdParty/mavlink/include/common/mavlink_msg_command_ack.h new file mode 100644 index 0000000000000000000000000000000000000000..32b39da3a6550341a6050d8d87bfa9834780fd73 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_command_ack.h @@ -0,0 +1,128 @@ +// MESSAGE COMMAND_ACK PACKING + +#define MAVLINK_MSG_ID_COMMAND_ACK 76 + +typedef struct __mavlink_command_ack_t +{ + float command; ///< Current airspeed in m/s + float result; ///< 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + +} mavlink_command_ack_t; + + + +/** + * @brief Pack a command_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param command Current airspeed in m/s + * @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float command, float result) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; + + i += put_float_by_index(command, i, msg->payload); // Current airspeed in m/s + i += put_float_by_index(result, i, msg->payload); // 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a command_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param command Current airspeed in m/s + * @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float command, float result) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; + + i += put_float_by_index(command, i, msg->payload); // Current airspeed in m/s + i += put_float_by_index(result, i, msg->payload); // 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a command_ack 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 command_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) +{ + return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result); +} + +/** + * @brief Send a command_ack message + * @param chan MAVLink channel to send the message + * + * @param command Current airspeed in m/s + * @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, float command, float result) +{ + mavlink_message_t msg; + mavlink_msg_command_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, command, result); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE COMMAND_ACK UNPACKING + +/** + * @brief Get field command from command_ack message + * + * @return Current airspeed in m/s + */ +static inline float mavlink_msg_command_ack_get_command(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 result from command_ack message + * + * @return 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + */ +static inline float mavlink_msg_command_ack_get_result(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 Decode a command_ack message into a struct + * + * @param msg The message to decode + * @param command_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack) +{ + command_ack->command = mavlink_msg_command_ack_get_command(msg); + command_ack->result = mavlink_msg_command_ack_get_result(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_control_status.h b/thirdParty/mavlink/include/common/mavlink_msg_control_status.h new file mode 100644 index 0000000000000000000000000000000000000000..746e889aafaf9d6b42e3bccccffbeb82a8d97f1d --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_control_status.h @@ -0,0 +1,220 @@ +// MESSAGE CONTROL_STATUS PACKING + +#define MAVLINK_MSG_ID_CONTROL_STATUS 52 + +typedef struct __mavlink_control_status_t +{ + uint8_t position_fix; ///< Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + uint8_t vision_fix; ///< Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + uint8_t gps_fix; ///< GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + uint8_t ahrs_health; ///< Attitude estimation health: 0: poor, 255: excellent + uint8_t control_att; ///< 0: Attitude control disabled, 1: enabled + uint8_t control_pos_xy; ///< 0: X, Y position control disabled, 1: enabled + uint8_t control_pos_z; ///< 0: Z position control disabled, 1: enabled + uint8_t control_pos_yaw; ///< 0: Yaw angle control disabled, 1: enabled + +} mavlink_control_status_t; + + + +/** + * @brief Pack a control_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent + * @param control_att 0: Attitude control disabled, 1: enabled + * @param control_pos_xy 0: X, Y position control disabled, 1: enabled + * @param control_pos_z 0: Z position control disabled, 1: enabled + * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_control_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS; + + i += put_uint8_t_by_index(position_fix, i, msg->payload); // Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + i += put_uint8_t_by_index(vision_fix, i, msg->payload); // Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + i += put_uint8_t_by_index(gps_fix, i, msg->payload); // GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + i += put_uint8_t_by_index(ahrs_health, i, msg->payload); // Attitude estimation health: 0: poor, 255: excellent + i += put_uint8_t_by_index(control_att, i, msg->payload); // 0: Attitude control disabled, 1: enabled + i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); // 0: X, Y position control disabled, 1: enabled + i += put_uint8_t_by_index(control_pos_z, i, msg->payload); // 0: Z position control disabled, 1: enabled + i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); // 0: Yaw angle control disabled, 1: enabled + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a control_status 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 position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent + * @param control_att 0: Attitude control disabled, 1: enabled + * @param control_pos_xy 0: X, Y position control disabled, 1: enabled + * @param control_pos_z 0: Z position control disabled, 1: enabled + * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_control_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS; + + i += put_uint8_t_by_index(position_fix, i, msg->payload); // Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + i += put_uint8_t_by_index(vision_fix, i, msg->payload); // Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + i += put_uint8_t_by_index(gps_fix, i, msg->payload); // GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + i += put_uint8_t_by_index(ahrs_health, i, msg->payload); // Attitude estimation health: 0: poor, 255: excellent + i += put_uint8_t_by_index(control_att, i, msg->payload); // 0: Attitude control disabled, 1: enabled + i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); // 0: X, Y position control disabled, 1: enabled + i += put_uint8_t_by_index(control_pos_z, i, msg->payload); // 0: Z position control disabled, 1: enabled + i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); // 0: Yaw angle control disabled, 1: enabled + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a control_status 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 control_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_control_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_status_t* control_status) +{ + return mavlink_msg_control_status_pack(system_id, component_id, msg, control_status->position_fix, control_status->vision_fix, control_status->gps_fix, control_status->ahrs_health, control_status->control_att, control_status->control_pos_xy, control_status->control_pos_z, control_status->control_pos_yaw); +} + +/** + * @brief Send a control_status message + * @param chan MAVLink channel to send the message + * + * @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent + * @param control_att 0: Attitude control disabled, 1: enabled + * @param control_pos_xy 0: X, Y position control disabled, 1: enabled + * @param control_pos_z 0: Z position control disabled, 1: enabled + * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_control_status_send(mavlink_channel_t chan, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw) +{ + mavlink_message_t msg; + mavlink_msg_control_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE CONTROL_STATUS UNPACKING + +/** + * @brief Get field position_fix from control_status message + * + * @return Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + */ +static inline uint8_t mavlink_msg_control_status_get_position_fix(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field vision_fix from control_status message + * + * @return Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + */ +static inline uint8_t mavlink_msg_control_status_get_vision_fix(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field gps_fix from control_status message + * + * @return GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + */ +static inline uint8_t mavlink_msg_control_status_get_gps_fix(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field ahrs_health from control_status message + * + * @return Attitude estimation health: 0: poor, 255: excellent + */ +static inline uint8_t mavlink_msg_control_status_get_ahrs_health(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field control_att from control_status message + * + * @return 0: Attitude control disabled, 1: enabled + */ +static inline uint8_t mavlink_msg_control_status_get_control_att(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field control_pos_xy from control_status message + * + * @return 0: X, Y position control disabled, 1: enabled + */ +static inline uint8_t mavlink_msg_control_status_get_control_pos_xy(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field control_pos_z from control_status message + * + * @return 0: Z position control disabled, 1: enabled + */ +static inline uint8_t mavlink_msg_control_status_get_control_pos_z(const mavlink_message_t* msg) +{ + 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 Get field control_pos_yaw from control_status message + * + * @return 0: Yaw angle control disabled, 1: enabled + */ +static inline uint8_t mavlink_msg_control_status_get_control_pos_yaw(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a control_status message into a struct + * + * @param msg The message to decode + * @param control_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_control_status_decode(const mavlink_message_t* msg, mavlink_control_status_t* control_status) +{ + control_status->position_fix = mavlink_msg_control_status_get_position_fix(msg); + control_status->vision_fix = mavlink_msg_control_status_get_vision_fix(msg); + control_status->gps_fix = mavlink_msg_control_status_get_gps_fix(msg); + control_status->ahrs_health = mavlink_msg_control_status_get_ahrs_health(msg); + control_status->control_att = mavlink_msg_control_status_get_control_att(msg); + control_status->control_pos_xy = mavlink_msg_control_status_get_control_pos_xy(msg); + control_status->control_pos_z = mavlink_msg_control_status_get_control_pos_z(msg); + control_status->control_pos_yaw = mavlink_msg_control_status_get_control_pos_yaw(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_debug.h b/thirdParty/mavlink/include/common/mavlink_msg_debug.h new file mode 100644 index 0000000000000000000000000000000000000000..e98be847ada748a728ca21b1234bdcb7eb9d5f01 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_debug.h @@ -0,0 +1,123 @@ +// MESSAGE DEBUG PACKING + +#define MAVLINK_MSG_ID_DEBUG 255 + +typedef struct __mavlink_debug_t +{ + uint8_t ind; ///< index of debug variable + float value; ///< DEBUG value + +} mavlink_debug_t; + + + +/** + * @brief Pack a debug message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param ind index of debug variable + * @param value DEBUG value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t ind, float value) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_DEBUG; + + i += put_uint8_t_by_index(ind, i, msg->payload); // index of debug variable + i += put_float_by_index(value, i, msg->payload); // DEBUG value + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a debug message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param ind index of debug variable + * @param value DEBUG value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t ind, float value) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_DEBUG; + + i += put_uint8_t_by_index(ind, i, msg->payload); // index of debug variable + i += put_float_by_index(value, i, msg->payload); // DEBUG value + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a debug 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 debug C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug) +{ + return mavlink_msg_debug_pack(system_id, component_id, msg, debug->ind, debug->value); +} + +/** + * @brief Send a debug message + * @param chan MAVLink channel to send the message + * + * @param ind index of debug variable + * @param value DEBUG value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, float value) +{ + mavlink_message_t msg; + mavlink_msg_debug_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, ind, value); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE DEBUG UNPACKING + +/** + * @brief Get field ind from debug message + * + * @return index of debug variable + */ +static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field value from debug message + * + * @return DEBUG value + */ +static inline float mavlink_msg_debug_get_value(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 Decode a debug message into a struct + * + * @param msg The message to decode + * @param debug C-struct to decode the message contents into + */ +static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug) +{ + debug->ind = mavlink_msg_debug_get_ind(msg); + debug->value = mavlink_msg_debug_get_value(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_debug_vect.h b/thirdParty/mavlink/include/common/mavlink_msg_debug_vect.h new file mode 100644 index 0000000000000000000000000000000000000000..6ea9e0558bf73d5956de6cc279a33f1d78bc0e28 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_debug_vect.h @@ -0,0 +1,196 @@ +// MESSAGE DEBUG_VECT PACKING + +#define MAVLINK_MSG_ID_DEBUG_VECT 251 + +typedef struct __mavlink_debug_vect_t +{ + char 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 Pack a debug_vect message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param name Name + * @param usec Timestamp + * @param x x + * @param y y + * @param z z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, uint64_t usec, float x, float y, float z) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; + + i += put_array_by_index((const int8_t*)name, sizeof(char)*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); +} + +/** + * @brief Pack a debug_vect message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param name Name + * @param usec Timestamp + * @param x x + * @param y y + * @param z z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, uint64_t usec, float x, float y, float z) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; + + i += put_array_by_index((const int8_t*)name, sizeof(char)*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); +} + +/** + * @brief Encode a debug_vect 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 debug_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) +{ + return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z); +} + +/** + * @brief Send a debug_vect message + * @param chan MAVLink channel to send the message + * + * @param name Name + * @param usec Timestamp + * @param x x + * @param y y + * @param z z + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char* name, uint64_t 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, char* r_data) +{ + + memcpy(r_data, msg->payload, sizeof(char)*10); + return sizeof(char)*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+sizeof(char)*10)[0]; + r.b[6] = (msg->payload+sizeof(char)*10)[1]; + r.b[5] = (msg->payload+sizeof(char)*10)[2]; + r.b[4] = (msg->payload+sizeof(char)*10)[3]; + r.b[3] = (msg->payload+sizeof(char)*10)[4]; + r.b[2] = (msg->payload+sizeof(char)*10)[5]; + r.b[1] = (msg->payload+sizeof(char)*10)[6]; + r.b[0] = (msg->payload+sizeof(char)*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+sizeof(char)*10+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(char)*10+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(char)*10+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(char)*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+sizeof(char)*10+sizeof(uint64_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(char)*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+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a debug_vect message into a struct + * + * @param msg The message to decode + * @param debug_vect C-struct to decode the message contents into + */ +static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect) +{ + 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); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_global_position.h b/thirdParty/mavlink/include/common/mavlink_msg_global_position.h new file mode 100644 index 0000000000000000000000000000000000000000..9d27f7714bcacb8c87d7706ee67a6cb2ecaea5bd --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_global_position.h @@ -0,0 +1,242 @@ +// MESSAGE GLOBAL_POSITION PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION 33 + +typedef struct __mavlink_global_position_t +{ + uint64_t usec; ///< Timestamp (microseconds since unix epoch) + float lat; ///< Latitude, in degrees + float lon; ///< Longitude, in degrees + float alt; ///< Absolute altitude, in meters + float vx; ///< X Speed (in Latitude direction, positive: going north) + float vy; ///< Y Speed (in Longitude direction, positive: going east) + float vz; ///< Z Speed (in Altitude direction, positive: going up) + +} mavlink_global_position_t; + + + +/** + * @brief Pack a global_position message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since unix epoch) + * @param lat Latitude, in degrees + * @param lon Longitude, in degrees + * @param alt Absolute altitude, in meters + * @param vx X Speed (in Latitude direction, positive: going north) + * @param vy Y Speed (in Longitude direction, positive: going east) + * @param vz Z Speed (in Altitude direction, positive: going up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch) + i += put_float_by_index(lat, i, msg->payload); // Latitude, in degrees + i += put_float_by_index(lon, i, msg->payload); // Longitude, in degrees + i += put_float_by_index(alt, i, msg->payload); // Absolute altitude, in meters + i += put_float_by_index(vx, i, msg->payload); // X Speed (in Latitude direction, positive: going north) + i += put_float_by_index(vy, i, msg->payload); // Y Speed (in Longitude direction, positive: going east) + i += put_float_by_index(vz, i, msg->payload); // Z Speed (in Altitude direction, positive: going up) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a global_position message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds since unix epoch) + * @param lat Latitude, in degrees + * @param lon Longitude, in degrees + * @param alt Absolute altitude, in meters + * @param vx X Speed (in Latitude direction, positive: going north) + * @param vy Y Speed (in Longitude direction, positive: going east) + * @param vz Z Speed (in Altitude direction, positive: going up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch) + i += put_float_by_index(lat, i, msg->payload); // Latitude, in degrees + i += put_float_by_index(lon, i, msg->payload); // Longitude, in degrees + i += put_float_by_index(alt, i, msg->payload); // Absolute altitude, in meters + i += put_float_by_index(vx, i, msg->payload); // X Speed (in Latitude direction, positive: going north) + i += put_float_by_index(vy, i, msg->payload); // Y Speed (in Longitude direction, positive: going east) + i += put_float_by_index(vz, i, msg->payload); // Z Speed (in Altitude direction, positive: going up) + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a global_position struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position) +{ + return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz); +} + +/** + * @brief Send a global_position message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds since unix epoch) + * @param lat Latitude, in degrees + * @param lon Longitude, in degrees + * @param alt Absolute altitude, in meters + * @param vx X Speed (in Latitude direction, positive: going north) + * @param vy Y Speed (in Longitude direction, positive: going east) + * @param vz Z Speed (in Altitude direction, positive: going up) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz) +{ + mavlink_message_t msg; + mavlink_msg_global_position_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, lat, lon, alt, vx, vy, vz); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE GLOBAL_POSITION UNPACKING + +/** + * @brief Get field usec from global_position message + * + * @return Timestamp (microseconds since unix epoch) + */ +static inline uint64_t mavlink_msg_global_position_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field lat from global_position message + * + * @return Latitude, in degrees + */ +static inline float mavlink_msg_global_position_get_lat(const mavlink_message_t* msg) +{ + 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; +} + +/** + * @brief Get field lon from global_position message + * + * @return Longitude, in degrees + */ +static inline float mavlink_msg_global_position_get_lon(const mavlink_message_t* msg) +{ + 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; +} + +/** + * @brief Get field alt from global_position message + * + * @return Absolute altitude, in meters + */ +static inline float mavlink_msg_global_position_get_alt(const mavlink_message_t* msg) +{ + 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; +} + +/** + * @brief Get field vx from global_position message + * + * @return X Speed (in Latitude direction, positive: going north) + */ +static inline float mavlink_msg_global_position_get_vx(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vy from global_position message + * + * @return Y Speed (in Longitude direction, positive: going east) + */ +static inline float mavlink_msg_global_position_get_vy(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vz from global_position message + * + * @return Z Speed (in Altitude direction, positive: going up) + */ +static inline float mavlink_msg_global_position_get_vz(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a global_position message into a struct + * + * @param msg The message to decode + * @param global_position C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_decode(const mavlink_message_t* msg, mavlink_global_position_t* global_position) +{ + global_position->usec = mavlink_msg_global_position_get_usec(msg); + global_position->lat = mavlink_msg_global_position_get_lat(msg); + global_position->lon = mavlink_msg_global_position_get_lon(msg); + global_position->alt = mavlink_msg_global_position_get_alt(msg); + global_position->vx = mavlink_msg_global_position_get_vx(msg); + global_position->vy = mavlink_msg_global_position_get_vy(msg); + global_position->vz = mavlink_msg_global_position_get_vz(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_global_position_int.h b/thirdParty/mavlink/include/common/mavlink_msg_global_position_int.h new file mode 100644 index 0000000000000000000000000000000000000000..1b3277a35798fe947b90ac468baa6fd827d27124 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_global_position_int.h @@ -0,0 +1,210 @@ +// MESSAGE GLOBAL_POSITION_INT PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 73 + +typedef struct __mavlink_global_position_int_t +{ + int32_t lat; ///< Latitude, expressed as * 1E7 + int32_t lon; ///< Longitude, expressed as * 1E7 + int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters) + int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 + int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 + int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 + +} mavlink_global_position_int_t; + + + +/** + * @brief Pack a global_position_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; + + i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7 + i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7 + i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters) + i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100 + i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100 + i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a global_position_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; + + i += put_int32_t_by_index(lat, i, msg->payload); // Latitude, expressed as * 1E7 + i += put_int32_t_by_index(lon, i, msg->payload); // Longitude, expressed as * 1E7 + i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in meters, expressed as * 1000 (millimeters) + i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed (Latitude), expressed as m/s * 100 + i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed (Longitude), expressed as m/s * 100 + i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed (Altitude), expressed as m/s * 100 + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a global_position_int struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_position_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) +{ + return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->vx, global_position_int->vy, global_position_int->vz); +} + +/** + * @brief Send a global_position_int message + * @param chan MAVLink channel to send the message + * + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz) +{ + mavlink_message_t msg; + mavlink_msg_global_position_int_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, lat, lon, alt, vx, vy, vz); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE GLOBAL_POSITION_INT UNPACKING + +/** + * @brief Get field lat from global_position_int message + * + * @return Latitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg) +{ + 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 (int32_t)r.i; +} + +/** + * @brief Get field lon from global_position_int message + * + * @return Longitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(int32_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field alt from global_position_int message + * + * @return Altitude in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field vx from global_position_int message + * + * @return Ground X Speed (Latitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0]; + r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field vy from global_position_int message + * + * @return Ground Y Speed (Longitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field vz from global_position_int message + * + * @return Ground Z Speed (Altitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Decode a global_position_int message into a struct + * + * @param msg The message to decode + * @param global_position_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int) +{ + global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg); + global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg); + global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg); + global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg); + global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg); + global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_gps_local_origin_set.h b/thirdParty/mavlink/include/common/mavlink_msg_gps_local_origin_set.h new file mode 100644 index 0000000000000000000000000000000000000000..156252854157547196b2fd439aa83d0aa3e41026 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_gps_local_origin_set.h @@ -0,0 +1,150 @@ +// MESSAGE GPS_LOCAL_ORIGIN_SET PACKING + +#define MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET 49 + +typedef struct __mavlink_gps_local_origin_set_t +{ + int32_t latitude; ///< Latitude (WGS84), expressed as * 1E7 + int32_t longitude; ///< Longitude (WGS84), expressed as * 1E7 + int32_t altitude; ///< Altitude(WGS84), expressed as * 1000 + +} mavlink_gps_local_origin_set_t; + + + +/** + * @brief Pack a gps_local_origin_set message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param latitude Latitude (WGS84), expressed as * 1E7 + * @param longitude Longitude (WGS84), expressed as * 1E7 + * @param altitude Altitude(WGS84), expressed as * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_local_origin_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int32_t latitude, int32_t longitude, int32_t altitude) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET; + + i += put_int32_t_by_index(latitude, i, msg->payload); // Latitude (WGS84), expressed as * 1E7 + i += put_int32_t_by_index(longitude, i, msg->payload); // Longitude (WGS84), expressed as * 1E7 + i += put_int32_t_by_index(altitude, i, msg->payload); // Altitude(WGS84), expressed as * 1000 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a gps_local_origin_set 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 latitude Latitude (WGS84), expressed as * 1E7 + * @param longitude Longitude (WGS84), expressed as * 1E7 + * @param altitude Altitude(WGS84), expressed as * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_local_origin_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int32_t latitude, int32_t longitude, int32_t altitude) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET; + + i += put_int32_t_by_index(latitude, i, msg->payload); // Latitude (WGS84), expressed as * 1E7 + i += put_int32_t_by_index(longitude, i, msg->payload); // Longitude (WGS84), expressed as * 1E7 + i += put_int32_t_by_index(altitude, i, msg->payload); // Altitude(WGS84), expressed as * 1000 + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a gps_local_origin_set 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_local_origin_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_local_origin_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_local_origin_set_t* gps_local_origin_set) +{ + return mavlink_msg_gps_local_origin_set_pack(system_id, component_id, msg, gps_local_origin_set->latitude, gps_local_origin_set->longitude, gps_local_origin_set->altitude); +} + +/** + * @brief Send a gps_local_origin_set message + * @param chan MAVLink channel to send the message + * + * @param latitude Latitude (WGS84), expressed as * 1E7 + * @param longitude Longitude (WGS84), expressed as * 1E7 + * @param altitude Altitude(WGS84), expressed as * 1000 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_local_origin_set_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) +{ + mavlink_message_t msg; + mavlink_msg_gps_local_origin_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, latitude, longitude, altitude); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE GPS_LOCAL_ORIGIN_SET UNPACKING + +/** + * @brief Get field latitude from gps_local_origin_set message + * + * @return Latitude (WGS84), expressed as * 1E7 + */ +static inline int32_t mavlink_msg_gps_local_origin_set_get_latitude(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 (int32_t)r.i; +} + +/** + * @brief Get field longitude from gps_local_origin_set message + * + * @return Longitude (WGS84), expressed as * 1E7 + */ +static inline int32_t mavlink_msg_gps_local_origin_set_get_longitude(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(int32_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field altitude from gps_local_origin_set message + * + * @return Altitude(WGS84), expressed as * 1000 + */ +static inline int32_t mavlink_msg_gps_local_origin_set_get_altitude(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Decode a gps_local_origin_set message into a struct + * + * @param msg The message to decode + * @param gps_local_origin_set C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_local_origin_set_decode(const mavlink_message_t* msg, mavlink_gps_local_origin_set_t* gps_local_origin_set) +{ + gps_local_origin_set->latitude = mavlink_msg_gps_local_origin_set_get_latitude(msg); + gps_local_origin_set->longitude = mavlink_msg_gps_local_origin_set_get_longitude(msg); + gps_local_origin_set->altitude = mavlink_msg_gps_local_origin_set_get_altitude(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_gps_raw.h b/thirdParty/mavlink/include/common/mavlink_msg_gps_raw.h new file mode 100644 index 0000000000000000000000000000000000000000..52d33a23b23a4aca8fab0ce8c9b1308dc3104e72 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_gps_raw.h @@ -0,0 +1,281 @@ +// MESSAGE GPS_RAW PACKING + +#define MAVLINK_MSG_ID_GPS_RAW 32 + +typedef struct __mavlink_gps_raw_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + float lat; ///< Latitude in degrees + float lon; ///< Longitude in degrees + float alt; ///< Altitude in meters + float eph; ///< GPS HDOP + float epv; ///< GPS VDOP + float v; ///< GPS ground speed + float hdg; ///< Compass heading in degrees, 0..360 degrees + +} mavlink_gps_raw_t; + + + +/** + * @brief Pack a gps_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param eph GPS HDOP + * @param epv GPS VDOP + * @param v GPS ground speed + * @param hdg Compass heading in degrees, 0..360 degrees + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GPS_RAW; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees + i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees + i += put_float_by_index(alt, i, msg->payload); // Altitude in meters + i += put_float_by_index(eph, i, msg->payload); // GPS HDOP + i += put_float_by_index(epv, i, msg->payload); // GPS VDOP + i += put_float_by_index(v, i, msg->payload); // GPS ground speed + i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a gps_raw 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param eph GPS HDOP + * @param epv GPS VDOP + * @param v GPS ground speed + * @param hdg Compass heading in degrees, 0..360 degrees + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GPS_RAW; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees + i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees + i += put_float_by_index(alt, i, msg->payload); // Altitude in meters + i += put_float_by_index(eph, i, msg->payload); // GPS HDOP + i += put_float_by_index(epv, i, msg->payload); // GPS VDOP + i += put_float_by_index(v, i, msg->payload); // GPS ground speed + i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a gps_raw 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_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw) +{ + return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg); +} + +/** + * @brief Send a gps_raw message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param eph GPS HDOP + * @param epv GPS VDOP + * @param v GPS ground speed + * @param hdg Compass heading in degrees, 0..360 degrees + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg) +{ + mavlink_message_t msg; + mavlink_msg_gps_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, fix_type, lat, lon, alt, eph, epv, v, hdg); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE GPS_RAW UNPACKING + +/** + * @brief Get field usec from gps_raw message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field fix_type from gps_raw message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + */ +static inline uint8_t mavlink_msg_gps_raw_get_fix_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint64_t))[0]; +} + +/** + * @brief Get field lat from gps_raw message + * + * @return Latitude in degrees + */ +static inline float mavlink_msg_gps_raw_get_lat(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field lon from gps_raw message + * + * @return Longitude in degrees + */ +static inline float mavlink_msg_gps_raw_get_lon(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field alt from gps_raw message + * + * @return Altitude in meters + */ +static inline float mavlink_msg_gps_raw_get_alt(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field eph from gps_raw message + * + * @return GPS HDOP + */ +static inline float mavlink_msg_gps_raw_get_eph(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field epv from gps_raw message + * + * @return GPS VDOP + */ +static inline float mavlink_msg_gps_raw_get_epv(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field v from gps_raw message + * + * @return GPS ground speed + */ +static inline float mavlink_msg_gps_raw_get_v(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field hdg from gps_raw message + * + * @return Compass heading in degrees, 0..360 degrees + */ +static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a gps_raw message into a struct + * + * @param msg The message to decode + * @param gps_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_raw_decode(const mavlink_message_t* msg, mavlink_gps_raw_t* gps_raw) +{ + gps_raw->usec = mavlink_msg_gps_raw_get_usec(msg); + gps_raw->fix_type = mavlink_msg_gps_raw_get_fix_type(msg); + gps_raw->lat = mavlink_msg_gps_raw_get_lat(msg); + gps_raw->lon = mavlink_msg_gps_raw_get_lon(msg); + gps_raw->alt = mavlink_msg_gps_raw_get_alt(msg); + gps_raw->eph = mavlink_msg_gps_raw_get_eph(msg); + gps_raw->epv = mavlink_msg_gps_raw_get_epv(msg); + gps_raw->v = mavlink_msg_gps_raw_get_v(msg); + gps_raw->hdg = mavlink_msg_gps_raw_get_hdg(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_gps_raw_int.h b/thirdParty/mavlink/include/common/mavlink_msg_gps_raw_int.h new file mode 100644 index 0000000000000000000000000000000000000000..b49498febc6519f905ade7271b9c607910488511 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_gps_raw_int.h @@ -0,0 +1,281 @@ +// MESSAGE GPS_RAW_INT PACKING + +#define MAVLINK_MSG_ID_GPS_RAW_INT 25 + +typedef struct __mavlink_gps_raw_int_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + int32_t lat; ///< Latitude in 1E7 degrees + int32_t lon; ///< Longitude in 1E7 degrees + int32_t alt; ///< Altitude in 1E3 meters (millimeters) + float eph; ///< GPS HDOP + float epv; ///< GPS VDOP + float v; ///< GPS ground speed (m/s) + float hdg; ///< Compass heading in degrees, 0..360 degrees + +} mavlink_gps_raw_int_t; + + + +/** + * @brief Pack a gps_raw_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in 1E7 degrees + * @param lon Longitude in 1E7 degrees + * @param alt Altitude in 1E3 meters (millimeters) + * @param eph GPS HDOP + * @param epv GPS VDOP + * @param v GPS ground speed (m/s) + * @param hdg Compass heading in degrees, 0..360 degrees + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + i += put_int32_t_by_index(lat, i, msg->payload); // Latitude in 1E7 degrees + i += put_int32_t_by_index(lon, i, msg->payload); // Longitude in 1E7 degrees + i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in 1E3 meters (millimeters) + i += put_float_by_index(eph, i, msg->payload); // GPS HDOP + i += put_float_by_index(epv, i, msg->payload); // GPS VDOP + i += put_float_by_index(v, i, msg->payload); // GPS ground speed (m/s) + i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a gps_raw_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param 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 fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in 1E7 degrees + * @param lon Longitude in 1E7 degrees + * @param alt Altitude in 1E3 meters (millimeters) + * @param eph GPS HDOP + * @param epv GPS VDOP + * @param v GPS ground speed (m/s) + * @param hdg Compass heading in degrees, 0..360 degrees + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + i += put_int32_t_by_index(lat, i, msg->payload); // Latitude in 1E7 degrees + i += put_int32_t_by_index(lon, i, msg->payload); // Longitude in 1E7 degrees + i += put_int32_t_by_index(alt, i, msg->payload); // Altitude in 1E3 meters (millimeters) + i += put_float_by_index(eph, i, msg->payload); // GPS HDOP + i += put_float_by_index(epv, i, msg->payload); // GPS VDOP + i += put_float_by_index(v, i, msg->payload); // GPS ground speed (m/s) + i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a gps_raw_int 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_raw_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) +{ + return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->v, gps_raw_int->hdg); +} + +/** + * @brief Send a gps_raw_int message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in 1E7 degrees + * @param lon Longitude in 1E7 degrees + * @param alt Altitude in 1E3 meters (millimeters) + * @param eph GPS HDOP + * @param epv GPS VDOP + * @param v GPS ground speed (m/s) + * @param hdg Compass heading in degrees, 0..360 degrees + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg) +{ + mavlink_message_t msg; + mavlink_msg_gps_raw_int_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, fix_type, lat, lon, alt, eph, epv, v, hdg); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE GPS_RAW_INT UNPACKING + +/** + * @brief Get field usec from gps_raw_int message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_gps_raw_int_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field fix_type from gps_raw_int message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + */ +static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint64_t))[0]; +} + +/** + * @brief Get field lat from gps_raw_int message + * + * @return Latitude in 1E7 degrees + */ +static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field lon from gps_raw_int message + * + * @return Longitude in 1E7 degrees + */ +static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field alt from gps_raw_int message + * + * @return Altitude in 1E3 meters (millimeters) + */ +static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field eph from gps_raw_int message + * + * @return GPS HDOP + */ +static inline float mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field epv from gps_raw_int message + * + * @return GPS VDOP + */ +static inline float mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field v from gps_raw_int message + * + * @return GPS ground speed (m/s) + */ +static inline float mavlink_msg_gps_raw_int_get_v(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field hdg from gps_raw_int message + * + * @return Compass heading in degrees, 0..360 degrees + */ +static inline float mavlink_msg_gps_raw_int_get_hdg(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a gps_raw_int message into a struct + * + * @param msg The message to decode + * @param gps_raw_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int) +{ + gps_raw_int->usec = mavlink_msg_gps_raw_int_get_usec(msg); + gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg); + gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg); + gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg); + gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg); + gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg); + gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg); + gps_raw_int->v = mavlink_msg_gps_raw_int_get_v(msg); + gps_raw_int->hdg = mavlink_msg_gps_raw_int_get_hdg(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_gps_set_global_origin.h b/thirdParty/mavlink/include/common/mavlink_msg_gps_set_global_origin.h new file mode 100644 index 0000000000000000000000000000000000000000..47ddc2e23b90a31fe6f6c3efa43a4e68735c0f4b --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_gps_set_global_origin.h @@ -0,0 +1,184 @@ +// MESSAGE GPS_SET_GLOBAL_ORIGIN PACKING + +#define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN 48 + +typedef struct __mavlink_gps_set_global_origin_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + int32_t latitude; ///< global position * 1E7 + int32_t longitude; ///< global position * 1E7 + int32_t altitude; ///< global position * 1000 + +} mavlink_gps_set_global_origin_t; + + + +/** + * @brief Pack a gps_set_global_origin message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude) +{ + 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_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); +} + +/** + * @brief Pack a gps_set_global_origin message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude) +{ + 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_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); +} + +/** + * @brief Encode a gps_set_global_origin struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_set_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_set_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_set_global_origin_t* gps_set_global_origin) +{ + return mavlink_msg_gps_set_global_origin_pack(system_id, component_id, msg, gps_set_global_origin->target_system, gps_set_global_origin->target_component, gps_set_global_origin->latitude, gps_set_global_origin->longitude, gps_set_global_origin->altitude); +} + +/** + * @brief Send a gps_set_global_origin message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude) +{ + 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); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE GPS_SET_GLOBAL_ORIGIN UNPACKING + +/** + * @brief Get field target_system from gps_set_global_origin message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from gps_set_global_origin message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field latitude from gps_set_global_origin message + * + * @return global position * 1E7 + */ +static inline int32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg) +{ + 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 (int32_t)r.i; +} + +/** + * @brief Get field longitude from gps_set_global_origin message + * + * @return global position * 1E7 + */ +static inline int32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg) +{ + generic_32bit r; + 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; +} + +/** + * @brief Get field altitude from gps_set_global_origin message + * + * @return global position * 1000 + */ +static inline int32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg) +{ + generic_32bit r; + 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; +} + +/** + * @brief Decode a gps_set_global_origin message into a struct + * + * @param msg The message to decode + * @param gps_set_global_origin C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_set_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_set_global_origin_t* gps_set_global_origin) +{ + gps_set_global_origin->target_system = mavlink_msg_gps_set_global_origin_get_target_system(msg); + gps_set_global_origin->target_component = mavlink_msg_gps_set_global_origin_get_target_component(msg); + gps_set_global_origin->latitude = mavlink_msg_gps_set_global_origin_get_latitude(msg); + gps_set_global_origin->longitude = mavlink_msg_gps_set_global_origin_get_longitude(msg); + gps_set_global_origin->altitude = mavlink_msg_gps_set_global_origin_get_altitude(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_gps_status.h b/thirdParty/mavlink/include/common/mavlink_msg_gps_status.h new file mode 100644 index 0000000000000000000000000000000000000000..fd04a9a262f39d53f5a566d977a6112dbe9d6add --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_gps_status.h @@ -0,0 +1,201 @@ +// MESSAGE GPS_STATUS PACKING + +#define MAVLINK_MSG_ID_GPS_STATUS 27 + +typedef struct __mavlink_gps_status_t +{ + uint8_t satellites_visible; ///< Number of satellites visible + int8_t satellite_prn[20]; ///< Global satellite ID + int8_t satellite_used[20]; ///< 0: Satellite not used, 1: used for localization + int8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite + int8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg. + int8_t satellite_snr[20]; ///< Signal to noise ratio of satellite + +} mavlink_gps_status_t; + +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20 + + +/** + * @brief Pack a gps_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; + + i += put_uint8_t_by_index(satellites_visible, i, msg->payload); // Number of satellites visible + i += put_array_by_index(satellite_prn, 20, i, msg->payload); // Global satellite ID + i += put_array_by_index(satellite_used, 20, i, msg->payload); // 0: Satellite not used, 1: used for localization + i += put_array_by_index(satellite_elevation, 20, i, msg->payload); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite + i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); // Direction of satellite, 0: 0 deg, 255: 360 deg. + i += put_array_by_index(satellite_snr, 20, i, msg->payload); // Signal to noise ratio of satellite + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a gps_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; + + i += put_uint8_t_by_index(satellites_visible, i, msg->payload); // Number of satellites visible + i += put_array_by_index(satellite_prn, 20, i, msg->payload); // Global satellite ID + i += put_array_by_index(satellite_used, 20, i, msg->payload); // 0: Satellite not used, 1: used for localization + i += put_array_by_index(satellite_elevation, 20, i, msg->payload); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite + i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); // Direction of satellite, 0: 0 deg, 255: 360 deg. + i += put_array_by_index(satellite_snr, 20, i, msg->payload); // Signal to noise ratio of satellite + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a gps_status 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_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) +{ + return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); +} + +/** + * @brief Send a gps_status message + * @param chan MAVLink channel to send the message + * + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr) +{ + mavlink_message_t msg; + mavlink_msg_gps_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE GPS_STATUS UNPACKING + +/** + * @brief Get field satellites_visible from gps_status message + * + * @return Number of satellites visible + */ +static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field satellite_prn from gps_status message + * + * @return Global satellite ID + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t), 20); + return 20; +} + +/** + * @brief Get field satellite_used from gps_status message + * + * @return 0: Satellite not used, 1: used for localization + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+20, 20); + return 20; +} + +/** + * @brief Get field satellite_elevation from gps_status message + * + * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20, 20); + return 20; +} + +/** + * @brief Get field satellite_azimuth from gps_status message + * + * @return Direction of satellite, 0: 0 deg, 255: 360 deg. + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20+20, 20); + return 20; +} + +/** + * @brief Get field satellite_snr from gps_status message + * + * @return Signal to noise ratio of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20+20+20, 20); + return 20; +} + +/** + * @brief Decode a gps_status message into a struct + * + * @param msg The message to decode + * @param gps_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status) +{ + gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg); + mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn); + mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used); + mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation); + mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth); + mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_heartbeat.h b/thirdParty/mavlink/include/common/mavlink_msg_heartbeat.h new file mode 100644 index 0000000000000000000000000000000000000000..0e5c4db5ca00fb627f2c5072cd8b2d1d7cbd02ad --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_heartbeat.h @@ -0,0 +1,132 @@ +// MESSAGE HEARTBEAT PACKING + +#define MAVLINK_MSG_ID_HEARTBEAT 0 + +typedef struct __mavlink_heartbeat_t +{ + uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + uint8_t autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + uint8_t mavlink_version; ///< MAVLink version + +} mavlink_heartbeat_t; + + + +/** + * @brief Pack a heartbeat message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t autopilot) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; + + i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + i += put_uint8_t_by_index(2, i, msg->payload); // MAVLink version + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a heartbeat message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t autopilot) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; + + i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + i += put_uint8_t_by_index(2, i, msg->payload); // MAVLink version + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a heartbeat 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 heartbeat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) +{ + return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot); +} + +/** + * @brief Send a heartbeat message + * @param chan MAVLink channel to send the message + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot) +{ + mavlink_message_t msg; + mavlink_msg_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, autopilot); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE HEARTBEAT UNPACKING + +/** + * @brief Get field type from heartbeat message + * + * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + */ +static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field autopilot from heartbeat message + * + * @return Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field mavlink_version from heartbeat message + * + * @return MAVLink version + */ +static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a heartbeat message into a struct + * + * @param msg The message to decode + * @param heartbeat C-struct to decode the message contents into + */ +static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) +{ + heartbeat->type = mavlink_msg_heartbeat_get_type(msg); + heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); + heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_local_position.h b/thirdParty/mavlink/include/common/mavlink_msg_local_position.h new file mode 100644 index 0000000000000000000000000000000000000000..c9cb453c0e0dd4e5ef4aa771b7612a5aa30ca6db --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_local_position.h @@ -0,0 +1,242 @@ +// MESSAGE LOCAL_POSITION PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION 31 + +typedef struct __mavlink_local_position_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + float x; ///< X Position + float y; ///< Y Position + float z; ///< Z Position + float vx; ///< X Speed + float vy; ///< Y Speed + float vz; ///< Z Speed + +} mavlink_local_position_t; + + + +/** + * @brief Pack a local_position message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float vx, float vy, float vz) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION; + + 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(x, i, msg->payload); // X Position + i += put_float_by_index(y, i, msg->payload); // Y Position + i += put_float_by_index(z, i, msg->payload); // Z Position + i += put_float_by_index(vx, i, msg->payload); // X Speed + i += put_float_by_index(vy, i, msg->payload); // Y Speed + i += put_float_by_index(vz, i, msg->payload); // Z Speed + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a local_position 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float vx, float vy, float vz) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION; + + 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(x, i, msg->payload); // X Position + i += put_float_by_index(y, i, msg->payload); // Y Position + i += put_float_by_index(z, i, msg->payload); // Z Position + i += put_float_by_index(vx, i, msg->payload); // X Speed + i += put_float_by_index(vy, i, msg->payload); // Y Speed + i += put_float_by_index(vz, i, msg->payload); // Z Speed + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a local_position struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_t* local_position) +{ + return mavlink_msg_local_position_pack(system_id, component_id, msg, local_position->usec, local_position->x, local_position->y, local_position->z, local_position->vx, local_position->vy, local_position->vz); +} + +/** + * @brief Send a local_position message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float vx, float vy, float vz) +{ + mavlink_message_t msg; + mavlink_msg_local_position_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z, vx, vy, vz); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE LOCAL_POSITION UNPACKING + +/** + * @brief Get field usec from local_position message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_local_position_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field x from local_position message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_get_x(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; +} + +/** + * @brief Get field y from local_position message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_get_y(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; +} + +/** + * @brief Get field z from local_position message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_get_z(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; +} + +/** + * @brief Get field vx from local_position message + * + * @return X Speed + */ +static inline float mavlink_msg_local_position_get_vx(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vy from local_position message + * + * @return Y Speed + */ +static inline float mavlink_msg_local_position_get_vy(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field vz from local_position message + * + * @return Z Speed + */ +static inline float mavlink_msg_local_position_get_vz(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a local_position message into a struct + * + * @param msg The message to decode + * @param local_position C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_decode(const mavlink_message_t* msg, mavlink_local_position_t* local_position) +{ + local_position->usec = mavlink_msg_local_position_get_usec(msg); + local_position->x = mavlink_msg_local_position_get_x(msg); + local_position->y = mavlink_msg_local_position_get_y(msg); + local_position->z = mavlink_msg_local_position_get_z(msg); + local_position->vx = mavlink_msg_local_position_get_vx(msg); + local_position->vy = mavlink_msg_local_position_get_vy(msg); + local_position->vz = mavlink_msg_local_position_get_vz(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_local_position_setpoint.h b/thirdParty/mavlink/include/common/mavlink_msg_local_position_setpoint.h new file mode 100644 index 0000000000000000000000000000000000000000..fcf4733476ec7c3312819ebac11a91a0d10ba1c5 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_local_position_setpoint.h @@ -0,0 +1,172 @@ +// MESSAGE LOCAL_POSITION_SETPOINT PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51 + +typedef struct __mavlink_local_position_setpoint_t +{ + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< Desired yaw angle + +} mavlink_local_position_setpoint_t; + + + +/** + * @brief Pack a local_position_setpoint 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 x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; + + i += put_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a local_position_setpoint 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 x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; + + i += put_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a local_position_setpoint 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 local_position_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint) +{ + return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw); +} + +/** + * @brief Send a local_position_setpoint message + * @param chan MAVLink channel to send the message + * + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_local_position_setpoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE LOCAL_POSITION_SETPOINT UNPACKING + +/** + * @brief Get field x from local_position_setpoint message + * + * @return x position + */ +static inline float mavlink_msg_local_position_setpoint_get_x(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 y from local_position_setpoint message + * + * @return y position + */ +static inline float mavlink_msg_local_position_setpoint_get_y(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 z from local_position_setpoint message + * + * @return z position + */ +static inline float mavlink_msg_local_position_setpoint_get_z(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 yaw from local_position_setpoint message + * + * @return Desired yaw angle + */ +static inline float mavlink_msg_local_position_setpoint_get_yaw(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 Decode a local_position_setpoint message into a struct + * + * @param msg The message to decode + * @param local_position_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_t* local_position_setpoint) +{ + local_position_setpoint->x = mavlink_msg_local_position_setpoint_get_x(msg); + local_position_setpoint->y = mavlink_msg_local_position_setpoint_get_y(msg); + local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg); + local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_local_position_setpoint_set.h b/thirdParty/mavlink/include/common/mavlink_msg_local_position_setpoint_set.h new file mode 100644 index 0000000000000000000000000000000000000000..f3383287eb40a3154f961b5698f0208d1b13f1c9 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_local_position_setpoint_set.h @@ -0,0 +1,206 @@ +// MESSAGE LOCAL_POSITION_SETPOINT_SET PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET 50 + +typedef struct __mavlink_local_position_setpoint_set_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< Desired yaw angle + +} mavlink_local_position_setpoint_set_t; + + + +/** + * @brief Pack a local_position_setpoint_set message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET; + + 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_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a local_position_setpoint_set 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 System ID + * @param target_component Component ID + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_setpoint_set_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 x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET; + + 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_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a local_position_setpoint_set 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 local_position_setpoint_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_set_t* local_position_setpoint_set) +{ + return mavlink_msg_local_position_setpoint_set_pack(system_id, component_id, msg, local_position_setpoint_set->target_system, local_position_setpoint_set->target_component, local_position_setpoint_set->x, local_position_setpoint_set->y, local_position_setpoint_set->z, local_position_setpoint_set->yaw); +} + +/** + * @brief Send a local_position_setpoint_set message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_local_position_setpoint_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE LOCAL_POSITION_SETPOINT_SET UNPACKING + +/** + * @brief Get field target_system from local_position_setpoint_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_local_position_setpoint_set_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from local_position_setpoint_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_local_position_setpoint_set_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field x from local_position_setpoint_set message + * + * @return x position + */ +static inline float mavlink_msg_local_position_setpoint_set_get_x(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 y from local_position_setpoint_set message + * + * @return y position + */ +static inline float mavlink_msg_local_position_setpoint_set_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from local_position_setpoint_set message + * + * @return z position + */ +static inline float mavlink_msg_local_position_setpoint_set_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from local_position_setpoint_set message + * + * @return Desired yaw angle + */ +static inline float mavlink_msg_local_position_setpoint_set_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a local_position_setpoint_set message into a struct + * + * @param msg The message to decode + * @param local_position_setpoint_set C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_setpoint_set_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_set_t* local_position_setpoint_set) +{ + local_position_setpoint_set->target_system = mavlink_msg_local_position_setpoint_set_get_target_system(msg); + local_position_setpoint_set->target_component = mavlink_msg_local_position_setpoint_set_get_target_component(msg); + local_position_setpoint_set->x = mavlink_msg_local_position_setpoint_set_get_x(msg); + local_position_setpoint_set->y = mavlink_msg_local_position_setpoint_set_get_y(msg); + local_position_setpoint_set->z = mavlink_msg_local_position_setpoint_set_get_z(msg); + local_position_setpoint_set->yaw = mavlink_msg_local_position_setpoint_set_get_yaw(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_manual_control.h b/thirdParty/mavlink/include/common/mavlink_msg_manual_control.h new file mode 100644 index 0000000000000000000000000000000000000000..deec098f63c8cbd6779a077c96c5bf806e7bd308 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_manual_control.h @@ -0,0 +1,257 @@ +// MESSAGE MANUAL_CONTROL PACKING + +#define MAVLINK_MSG_ID_MANUAL_CONTROL 69 + +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 Pack a manual_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target 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); +} + +/** + * @brief Pack a manual_control 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 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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 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_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a manual_control 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 manual_control C-struct to read the message contents from + */ +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); +} + +/** + * @brief Send a manual_control message + * @param chan MAVLink channel to send the 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 + */ +#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_chan(mavlink_system.sysid, mavlink_system.compid, chan, &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]; +} + +/** + * @brief Decode a manual_control message into a struct + * + * @param msg The message to decode + * @param manual_control C-struct to decode the message contents into + */ +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); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_named_value_float.h b/thirdParty/mavlink/include/common/mavlink_msg_named_value_float.h new file mode 100644 index 0000000000000000000000000000000000000000..aaff215ce8cac16790d964a392624222902252c3 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_named_value_float.h @@ -0,0 +1,126 @@ +// MESSAGE NAMED_VALUE_FLOAT PACKING + +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 252 + +typedef struct __mavlink_named_value_float_t +{ + char name[10]; ///< Name of the debug variable + float value; ///< Floating point value + +} mavlink_named_value_float_t; + +#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10 + + +/** + * @brief Pack a named_value_float message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param name Name of the debug variable + * @param value Floating point value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, float value) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; + + i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable + i += put_float_by_index(value, i, msg->payload); // Floating point value + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a named_value_float 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 name Name of the debug variable + * @param value Floating point value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, float value) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; + + i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable + i += put_float_by_index(value, i, msg->payload); // Floating point value + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a named_value_float 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 named_value_float C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) +{ + return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->name, named_value_float->value); +} + +/** + * @brief Send a named_value_float message + * @param chan MAVLink channel to send the message + * + * @param name Name of the debug variable + * @param value Floating point value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, const char* name, float value) +{ + mavlink_message_t msg; + mavlink_msg_named_value_float_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, value); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE NAMED_VALUE_FLOAT UNPACKING + +/** + * @brief Get field name from named_value_float message + * + * @return Name of the debug variable + */ +static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char* r_data) +{ + + memcpy(r_data, msg->payload, sizeof(char)*10); + return sizeof(char)*10; +} + +/** + * @brief Get field value from named_value_float message + * + * @return Floating point value + */ +static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(char)*10)[0]; + r.b[2] = (msg->payload+sizeof(char)*10)[1]; + r.b[1] = (msg->payload+sizeof(char)*10)[2]; + r.b[0] = (msg->payload+sizeof(char)*10)[3]; + return (float)r.f; +} + +/** + * @brief Decode a named_value_float message into a struct + * + * @param msg The message to decode + * @param named_value_float C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float) +{ + mavlink_msg_named_value_float_get_name(msg, named_value_float->name); + named_value_float->value = mavlink_msg_named_value_float_get_value(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_named_value_int.h b/thirdParty/mavlink/include/common/mavlink_msg_named_value_int.h new file mode 100644 index 0000000000000000000000000000000000000000..92bf5fcb2a00dc154013dc64efe8f6dfc97a4ce4 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_named_value_int.h @@ -0,0 +1,126 @@ +// MESSAGE NAMED_VALUE_INT PACKING + +#define MAVLINK_MSG_ID_NAMED_VALUE_INT 253 + +typedef struct __mavlink_named_value_int_t +{ + char name[10]; ///< Name of the debug variable + int32_t value; ///< Signed integer value + +} mavlink_named_value_int_t; + +#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10 + + +/** + * @brief Pack a named_value_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param name Name of the debug variable + * @param value Signed integer value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, int32_t value) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; + + i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable + i += put_int32_t_by_index(value, i, msg->payload); // Signed integer value + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a named_value_int 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 name Name of the debug variable + * @param value Signed integer value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, int32_t value) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; + + i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable + i += put_int32_t_by_index(value, i, msg->payload); // Signed integer value + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a named_value_int 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 named_value_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) +{ + return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->name, named_value_int->value); +} + +/** + * @brief Send a named_value_int message + * @param chan MAVLink channel to send the message + * + * @param name Name of the debug variable + * @param value Signed integer value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, const char* name, int32_t value) +{ + mavlink_message_t msg; + mavlink_msg_named_value_int_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, value); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE NAMED_VALUE_INT UNPACKING + +/** + * @brief Get field name from named_value_int message + * + * @return Name of the debug variable + */ +static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char* r_data) +{ + + memcpy(r_data, msg->payload, sizeof(char)*10); + return sizeof(char)*10; +} + +/** + * @brief Get field value from named_value_int message + * + * @return Signed integer value + */ +static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(char)*10)[0]; + r.b[2] = (msg->payload+sizeof(char)*10)[1]; + r.b[1] = (msg->payload+sizeof(char)*10)[2]; + r.b[0] = (msg->payload+sizeof(char)*10)[3]; + return (int32_t)r.i; +} + +/** + * @brief Decode a named_value_int message into a struct + * + * @param msg The message to decode + * @param named_value_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int) +{ + mavlink_msg_named_value_int_get_name(msg, named_value_int->name); + named_value_int->value = mavlink_msg_named_value_int_get_value(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_nav_controller_output.h b/thirdParty/mavlink/include/common/mavlink_msg_nav_controller_output.h new file mode 100644 index 0000000000000000000000000000000000000000..8d0b81eb877a57469875d785f85215e4e941f071 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_nav_controller_output.h @@ -0,0 +1,254 @@ +// MESSAGE NAV_CONTROLLER_OUTPUT PACKING + +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 + +typedef struct __mavlink_nav_controller_output_t +{ + float nav_roll; ///< Current desired roll in degrees + float nav_pitch; ///< Current desired pitch in degrees + int16_t nav_bearing; ///< Current desired heading in degrees + int16_t target_bearing; ///< Bearing to current waypoint/target in degrees + uint16_t wp_dist; ///< Distance to active waypoint in meters + float alt_error; ///< Current altitude error in meters + float aspd_error; ///< Current airspeed error in meters/second + float xtrack_error; ///< Current crosstrack error on x-y plane in meters + +} mavlink_nav_controller_output_t; + + + +/** + * @brief Pack a nav_controller_output 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 nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current waypoint/target in degrees + * @param wp_dist Distance to active waypoint in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; + + i += put_float_by_index(nav_roll, i, msg->payload); // Current desired roll in degrees + i += put_float_by_index(nav_pitch, i, msg->payload); // Current desired pitch in degrees + i += put_int16_t_by_index(nav_bearing, i, msg->payload); // Current desired heading in degrees + i += put_int16_t_by_index(target_bearing, i, msg->payload); // Bearing to current waypoint/target in degrees + i += put_uint16_t_by_index(wp_dist, i, msg->payload); // Distance to active waypoint in meters + i += put_float_by_index(alt_error, i, msg->payload); // Current altitude error in meters + i += put_float_by_index(aspd_error, i, msg->payload); // Current airspeed error in meters/second + i += put_float_by_index(xtrack_error, i, msg->payload); // Current crosstrack error on x-y plane in meters + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a nav_controller_output 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 nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current waypoint/target in degrees + * @param wp_dist Distance to active waypoint in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; + + i += put_float_by_index(nav_roll, i, msg->payload); // Current desired roll in degrees + i += put_float_by_index(nav_pitch, i, msg->payload); // Current desired pitch in degrees + i += put_int16_t_by_index(nav_bearing, i, msg->payload); // Current desired heading in degrees + i += put_int16_t_by_index(target_bearing, i, msg->payload); // Bearing to current waypoint/target in degrees + i += put_uint16_t_by_index(wp_dist, i, msg->payload); // Distance to active waypoint in meters + i += put_float_by_index(alt_error, i, msg->payload); // Current altitude error in meters + i += put_float_by_index(aspd_error, i, msg->payload); // Current airspeed error in meters/second + i += put_float_by_index(xtrack_error, i, msg->payload); // Current crosstrack error on x-y plane in meters + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a nav_controller_output 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 nav_controller_output C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) +{ + return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); +} + +/** + * @brief Send a nav_controller_output message + * @param chan MAVLink channel to send the message + * + * @param nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current waypoint/target in degrees + * @param wp_dist Distance to active waypoint in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ + mavlink_message_t msg; + mavlink_msg_nav_controller_output_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING + +/** + * @brief Get field nav_roll from nav_controller_output message + * + * @return Current desired roll in degrees + */ +static inline float mavlink_msg_nav_controller_output_get_nav_roll(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 nav_pitch from nav_controller_output message + * + * @return Current desired pitch in degrees + */ +static inline float mavlink_msg_nav_controller_output_get_nav_pitch(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 nav_bearing from nav_controller_output message + * + * @return Current desired heading in degrees + */ +static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[0]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field target_bearing from nav_controller_output message + * + * @return Bearing to current waypoint/target in degrees + */ +static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field wp_dist from nav_controller_output message + * + * @return Distance to active waypoint in meters + */ +static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field alt_error from nav_controller_output message + * + * @return Current altitude error in meters + */ +static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field aspd_error from nav_controller_output message + * + * @return Current airspeed error in meters/second + */ +static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field xtrack_error from nav_controller_output message + * + * @return Current crosstrack error on x-y plane in meters + */ +static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a nav_controller_output message into a struct + * + * @param msg The message to decode + * @param nav_controller_output C-struct to decode the message contents into + */ +static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output) +{ + nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg); + nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg); + nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg); + nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg); + nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg); + nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg); + nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg); + nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_param_request_list.h b/thirdParty/mavlink/include/common/mavlink_msg_param_request_list.h new file mode 100644 index 0000000000000000000000000000000000000000..e4912fb591a68b8bd59e7c9c7c0915a5fbc56c20 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_param_request_list.h @@ -0,0 +1,118 @@ +// MESSAGE PARAM_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 + +typedef struct __mavlink_param_request_list_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + +} mavlink_param_request_list_t; + + + +/** + * @brief Pack a param_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; + + 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 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a param_request_list 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 System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_list_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 i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; + + 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 + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a param_request_list 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 param_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) +{ + return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component); +} + +/** + * @brief Send a param_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ + mavlink_message_t msg; + mavlink_msg_param_request_list_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PARAM_REQUEST_LIST UNPACKING + +/** + * @brief Get field target_system from param_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from param_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a param_request_list message into a struct + * + * @param msg The message to decode + * @param param_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list) +{ + param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg); + param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_param_request_read.h b/thirdParty/mavlink/include/common/mavlink_msg_param_request_read.h new file mode 100644 index 0000000000000000000000000000000000000000..2cd9d2932ee35c6f2f48f72bcf1140d6cef1541f --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_param_request_read.h @@ -0,0 +1,158 @@ +// MESSAGE PARAM_REQUEST_READ PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 + +typedef struct __mavlink_param_request_read_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + int8_t param_id[15]; ///< Onboard parameter id + int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier + +} mavlink_param_request_read_t; + +#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 15 + + +/** + * @brief Pack a param_request_read message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_index Parameter index. Send -1 to use the param ID field as identifier + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const int8_t* param_id, int16_t param_index) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; + + 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_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id + i += put_int16_t_by_index(param_index, i, msg->payload); // Parameter index. Send -1 to use the param ID field as identifier + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a param_request_read 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 System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_index Parameter index. Send -1 to use the param ID field as identifier + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_read_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, const int8_t* param_id, int16_t param_index) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; + + 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_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id + i += put_int16_t_by_index(param_index, i, msg->payload); // Parameter index. Send -1 to use the param ID field as identifier + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a param_request_read 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 param_request_read C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) +{ + return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); +} + +/** + * @brief Send a param_request_read message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_index Parameter index. Send -1 to use the param ID field as identifier + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t* param_id, int16_t param_index) +{ + mavlink_message_t msg; + mavlink_msg_param_request_read_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, param_id, param_index); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PARAM_REQUEST_READ UNPACKING + +/** + * @brief Get field target_system from param_request_read message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from param_request_read message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field param_id from param_request_read message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t), 15); + return 15; +} + +/** + * @brief Get field param_index from param_request_read message + * + * @return Parameter index. Send -1 to use the param ID field as identifier + */ +static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[1]; + return (int16_t)r.s; +} + +/** + * @brief Decode a param_request_read message into a struct + * + * @param msg The message to decode + * @param param_request_read C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read) +{ + param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg); + param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg); + mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id); + param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_param_set.h b/thirdParty/mavlink/include/common/mavlink_msg_param_set.h new file mode 100644 index 0000000000000000000000000000000000000000..de1c3140221526b23f87edd935f306dd4cdcf9f6 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_param_set.h @@ -0,0 +1,160 @@ +// MESSAGE PARAM_SET PACKING + +#define MAVLINK_MSG_ID_PARAM_SET 23 + +typedef struct __mavlink_param_set_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + int8_t param_id[15]; ///< Onboard parameter id + float param_value; ///< Onboard parameter value + +} mavlink_param_set_t; + +#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 15 + + +/** + * @brief Pack a param_set message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const int8_t* param_id, float param_value) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_SET; + + 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_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id + i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a param_set 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 System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_set_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, const int8_t* param_id, float param_value) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_SET; + + 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_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id + i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a param_set 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 param_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set) +{ + return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value); +} + +/** + * @brief Send a param_set message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t* param_id, float param_value) +{ + mavlink_message_t msg; + mavlink_msg_param_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, param_id, param_value); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PARAM_SET UNPACKING + +/** + * @brief Get field target_system from param_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from param_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field param_id from param_set message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t), 15); + return 15; +} + +/** + * @brief Get field param_value from param_set message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[3]; + return (float)r.f; +} + +/** + * @brief Decode a param_set message into a struct + * + * @param msg The message to decode + * @param param_set C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set) +{ + param_set->target_system = mavlink_msg_param_set_get_target_system(msg); + param_set->target_component = mavlink_msg_param_set_get_target_component(msg); + mavlink_msg_param_set_get_param_id(msg, param_set->param_id); + param_set->param_value = mavlink_msg_param_set_get_param_value(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_param_value.h b/thirdParty/mavlink/include/common/mavlink_msg_param_value.h new file mode 100644 index 0000000000000000000000000000000000000000..239c96c42f6f4303d16496f74ddf181e22cf4ee2 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_param_value.h @@ -0,0 +1,166 @@ +// MESSAGE PARAM_VALUE PACKING + +#define MAVLINK_MSG_ID_PARAM_VALUE 22 + +typedef struct __mavlink_param_value_t +{ + int8_t param_id[15]; ///< Onboard parameter id + float param_value; ///< Onboard parameter value + uint16_t param_count; ///< Total number of onboard parameters + uint16_t param_index; ///< Index of this onboard parameter + +} mavlink_param_value_t; + +#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 15 + + +/** + * @brief Pack a param_value 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 param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; + + i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id + i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value + i += put_uint16_t_by_index(param_count, i, msg->payload); // Total number of onboard parameters + i += put_uint16_t_by_index(param_index, i, msg->payload); // Index of this onboard parameter + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a param_value 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 param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; + + i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id + i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value + i += put_uint16_t_by_index(param_count, i, msg->payload); // Total number of onboard parameters + i += put_uint16_t_by_index(param_index, i, msg->payload); // Index of this onboard parameter + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a param_value 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 param_value C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value) +{ + return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_count, param_value->param_index); +} + +/** + * @brief Send a param_value message + * @param chan MAVLink channel to send the message + * + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index) +{ + mavlink_message_t msg; + mavlink_msg_param_value_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, param_id, param_value, param_count, param_index); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PARAM_VALUE UNPACKING + +/** + * @brief Get field param_id from param_value message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload, 15); + return 15; +} + +/** + * @brief Get field param_value from param_value message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+15)[0]; + r.b[2] = (msg->payload+15)[1]; + r.b[1] = (msg->payload+15)[2]; + r.b[0] = (msg->payload+15)[3]; + return (float)r.f; +} + +/** + * @brief Get field param_count from param_value message + * + * @return Total number of onboard parameters + */ +static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+15+sizeof(float))[0]; + r.b[0] = (msg->payload+15+sizeof(float))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field param_index from param_value message + * + * @return Index of this onboard parameter + */ +static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+15+sizeof(float)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+15+sizeof(float)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Decode a param_value message into a struct + * + * @param msg The message to decode + * @param param_value C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value) +{ + mavlink_msg_param_value_get_param_id(msg, param_value->param_id); + param_value->param_value = mavlink_msg_param_value_get_param_value(msg); + param_value->param_count = mavlink_msg_param_value_get_param_count(msg); + param_value->param_index = mavlink_msg_param_value_get_param_index(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_ping.h b/thirdParty/mavlink/include/common/mavlink_msg_ping.h new file mode 100644 index 0000000000000000000000000000000000000000..2a27b1e5cb4fbb6be7ab00ae89d9f310dd248346 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_ping.h @@ -0,0 +1,166 @@ +// MESSAGE PING PACKING + +#define MAVLINK_MSG_ID_PING 3 + +typedef struct __mavlink_ping_t +{ + uint32_t seq; ///< PING sequence + uint8_t target_system; ///< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + uint8_t target_component; ///< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + uint64_t time; ///< Unix timestamp in microseconds + +} mavlink_ping_t; + + + +/** + * @brief Pack a ping 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 seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param time Unix timestamp in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PING; + + i += put_uint32_t_by_index(seq, i, msg->payload); // PING sequence + i += put_uint8_t_by_index(target_system, i, msg->payload); // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + i += put_uint8_t_by_index(target_component, i, msg->payload); // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + i += put_uint64_t_by_index(time, i, msg->payload); // Unix timestamp in microseconds + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a ping 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 seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param time Unix timestamp in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PING; + + i += put_uint32_t_by_index(seq, i, msg->payload); // PING sequence + i += put_uint8_t_by_index(target_system, i, msg->payload); // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + i += put_uint8_t_by_index(target_component, i, msg->payload); // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + i += put_uint64_t_by_index(time, i, msg->payload); // Unix timestamp in microseconds + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a ping 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 ping C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping) +{ + return mavlink_msg_ping_pack(system_id, component_id, msg, ping->seq, ping->target_system, ping->target_component, ping->time); +} + +/** + * @brief Send a ping message + * @param chan MAVLink channel to send the message + * + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param time Unix timestamp in microseconds + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time) +{ + mavlink_message_t msg; + mavlink_msg_ping_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seq, target_system, target_component, time); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PING UNPACKING + +/** + * @brief Get field seq from ping message + * + * @return PING sequence + */ +static inline uint32_t mavlink_msg_ping_get_seq(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 (uint32_t)r.i; +} + +/** + * @brief Get field target_system from ping message + * + * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint32_t))[0]; +} + +/** + * @brief Get field target_component from ping message + * + * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint32_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field time from ping message + * + * @return Unix timestamp in microseconds + */ +static inline uint64_t mavlink_msg_ping_get_time(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[6] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[5] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[4] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[3]; + r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[4]; + r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[5]; + r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[6]; + r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Decode a ping message into a struct + * + * @param msg The message to decode + * @param ping C-struct to decode the message contents into + */ +static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping) +{ + ping->seq = mavlink_msg_ping_get_seq(msg); + ping->target_system = mavlink_msg_ping_get_target_system(msg); + ping->target_component = mavlink_msg_ping_get_target_component(msg); + ping->time = mavlink_msg_ping_get_time(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_position_controller_output.h b/thirdParty/mavlink/include/common/mavlink_msg_position_controller_output.h new file mode 100644 index 0000000000000000000000000000000000000000..389d9a2387a8b1b34fc02b5620811d42513af08a --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_position_controller_output.h @@ -0,0 +1,169 @@ +// MESSAGE POSITION_CONTROLLER_OUTPUT PACKING + +#define MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT 61 + +typedef struct __mavlink_position_controller_output_t +{ + uint8_t enabled; ///< 1: enabled, 0: disabled + int8_t x; ///< Position x: -128: -100%, 127: +100% + int8_t y; ///< Position y: -128: -100%, 127: +100% + int8_t z; ///< Position z: -128: -100%, 127: +100% + int8_t yaw; ///< Position yaw: -128: -100%, 127: +100% + +} mavlink_position_controller_output_t; + + + +/** + * @brief Pack a position_controller_output 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 enabled 1: enabled, 0: disabled + * @param x Position x: -128: -100%, 127: +100% + * @param y Position y: -128: -100%, 127: +100% + * @param z Position z: -128: -100%, 127: +100% + * @param yaw Position yaw: -128: -100%, 127: +100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t enabled, int8_t x, int8_t y, int8_t z, int8_t yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT; + + i += put_uint8_t_by_index(enabled, i, msg->payload); // 1: enabled, 0: disabled + i += put_int8_t_by_index(x, i, msg->payload); // Position x: -128: -100%, 127: +100% + i += put_int8_t_by_index(y, i, msg->payload); // Position y: -128: -100%, 127: +100% + i += put_int8_t_by_index(z, i, msg->payload); // Position z: -128: -100%, 127: +100% + i += put_int8_t_by_index(yaw, i, msg->payload); // Position yaw: -128: -100%, 127: +100% + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a position_controller_output 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 enabled 1: enabled, 0: disabled + * @param x Position x: -128: -100%, 127: +100% + * @param y Position y: -128: -100%, 127: +100% + * @param z Position z: -128: -100%, 127: +100% + * @param yaw Position yaw: -128: -100%, 127: +100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enabled, int8_t x, int8_t y, int8_t z, int8_t yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT; + + i += put_uint8_t_by_index(enabled, i, msg->payload); // 1: enabled, 0: disabled + i += put_int8_t_by_index(x, i, msg->payload); // Position x: -128: -100%, 127: +100% + i += put_int8_t_by_index(y, i, msg->payload); // Position y: -128: -100%, 127: +100% + i += put_int8_t_by_index(z, i, msg->payload); // Position z: -128: -100%, 127: +100% + i += put_int8_t_by_index(yaw, i, msg->payload); // Position yaw: -128: -100%, 127: +100% + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a position_controller_output 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 position_controller_output C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_controller_output_t* position_controller_output) +{ + return mavlink_msg_position_controller_output_pack(system_id, component_id, msg, position_controller_output->enabled, position_controller_output->x, position_controller_output->y, position_controller_output->z, position_controller_output->yaw); +} + +/** + * @brief Send a position_controller_output message + * @param chan MAVLink channel to send the message + * + * @param enabled 1: enabled, 0: disabled + * @param x Position x: -128: -100%, 127: +100% + * @param y Position y: -128: -100%, 127: +100% + * @param z Position z: -128: -100%, 127: +100% + * @param yaw Position yaw: -128: -100%, 127: +100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_controller_output_send(mavlink_channel_t chan, uint8_t enabled, int8_t x, int8_t y, int8_t z, int8_t yaw) +{ + mavlink_message_t msg; + mavlink_msg_position_controller_output_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, enabled, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POSITION_CONTROLLER_OUTPUT UNPACKING + +/** + * @brief Get field enabled from position_controller_output message + * + * @return 1: enabled, 0: disabled + */ +static inline uint8_t mavlink_msg_position_controller_output_get_enabled(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field x from position_controller_output message + * + * @return Position x: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_position_controller_output_get_x(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field y from position_controller_output message + * + * @return Position y: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_position_controller_output_get_y(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t))[0]; +} + +/** + * @brief Get field z from position_controller_output message + * + * @return Position z: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_position_controller_output_get_z(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t)+sizeof(int8_t))[0]; +} + +/** + * @brief Get field yaw from position_controller_output message + * + * @return Position yaw: -128: -100%, 127: +100% + */ +static inline int8_t mavlink_msg_position_controller_output_get_yaw(const mavlink_message_t* msg) +{ + return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t)+sizeof(int8_t)+sizeof(int8_t))[0]; +} + +/** + * @brief Decode a position_controller_output message into a struct + * + * @param msg The message to decode + * @param position_controller_output C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_controller_output_decode(const mavlink_message_t* msg, mavlink_position_controller_output_t* position_controller_output) +{ + position_controller_output->enabled = mavlink_msg_position_controller_output_get_enabled(msg); + position_controller_output->x = mavlink_msg_position_controller_output_get_x(msg); + position_controller_output->y = mavlink_msg_position_controller_output_get_y(msg); + position_controller_output->z = mavlink_msg_position_controller_output_get_z(msg); + position_controller_output->yaw = mavlink_msg_position_controller_output_get_yaw(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_position_target.h b/thirdParty/mavlink/include/common/mavlink_msg_position_target.h new file mode 100644 index 0000000000000000000000000000000000000000..d6e4da3dd4e2db91448c4d1d88ffe7a021ff39d4 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_position_target.h @@ -0,0 +1,172 @@ +// MESSAGE POSITION_TARGET PACKING + +#define MAVLINK_MSG_ID_POSITION_TARGET 63 + +typedef struct __mavlink_position_target_t +{ + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< yaw orientation in radians, 0 = NORTH + +} mavlink_position_target_t; + + + +/** + * @brief Pack a position_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET; + + i += put_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a position_target 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 x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET; + + i += put_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a position_target 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 position_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_t* position_target) +{ + return mavlink_msg_position_target_pack(system_id, component_id, msg, position_target->x, position_target->y, position_target->z, position_target->yaw); +} + +/** + * @brief Send a position_target message + * @param chan MAVLink channel to send the message + * + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_target_send(mavlink_channel_t chan, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_position_target_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POSITION_TARGET UNPACKING + +/** + * @brief Get field x from position_target message + * + * @return x position + */ +static inline float mavlink_msg_position_target_get_x(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 y from position_target message + * + * @return y position + */ +static inline float mavlink_msg_position_target_get_y(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 z from position_target message + * + * @return z position + */ +static inline float mavlink_msg_position_target_get_z(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 yaw from position_target message + * + * @return yaw orientation in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_target_get_yaw(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 Decode a position_target message into a struct + * + * @param msg The message to decode + * @param position_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_target_decode(const mavlink_message_t* msg, mavlink_position_target_t* position_target) +{ + position_target->x = mavlink_msg_position_target_get_x(msg); + position_target->y = mavlink_msg_position_target_get_y(msg); + position_target->z = mavlink_msg_position_target_get_z(msg); + position_target->yaw = mavlink_msg_position_target_get_yaw(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_raw_imu.h b/thirdParty/mavlink/include/common/mavlink_msg_raw_imu.h new file mode 100644 index 0000000000000000000000000000000000000000..4ded0b71198d53b814d3fa6fa9fbdd106a2e94fd --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_raw_imu.h @@ -0,0 +1,290 @@ +// MESSAGE RAW_IMU PACKING + +#define MAVLINK_MSG_ID_RAW_IMU 28 + +typedef struct __mavlink_raw_imu_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + int16_t xacc; ///< X acceleration (raw) + int16_t yacc; ///< Y acceleration (raw) + int16_t zacc; ///< Z acceleration (raw) + int16_t xgyro; ///< Angular speed around X axis (raw) + int16_t ygyro; ///< Angular speed around Y axis (raw) + int16_t zgyro; ///< Angular speed around Z axis (raw) + int16_t xmag; ///< X Magnetic field (raw) + int16_t ymag; ///< Y Magnetic field (raw) + int16_t zmag; ///< Z Magnetic field (raw) + +} mavlink_raw_imu_t; + + + +/** + * @brief Pack a raw_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RAW_IMU; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (raw) + i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (raw) + i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (raw) + i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (raw) + i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (raw) + i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (raw) + i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (raw) + i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (raw) + i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (raw) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a raw_imu 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RAW_IMU; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (raw) + i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (raw) + i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (raw) + i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (raw) + i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (raw) + i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (raw) + i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (raw) + i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (raw) + i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (raw) + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a raw_imu 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 raw_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) +{ + return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); +} + +/** + * @brief Send a raw_imu message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ + mavlink_message_t msg; + mavlink_msg_raw_imu_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RAW_IMU UNPACKING + +/** + * @brief Get field usec from raw_imu message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_raw_imu_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field xacc from raw_imu message + * + * @return X acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) +{ + 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 yacc from raw_imu message + * + * @return Y acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) +{ + 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 zacc from raw_imu message + * + * @return Z acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) +{ + 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 xgyro from raw_imu message + * + * @return Angular speed around X axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg) +{ + generic_16bit r; + 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; +} + +/** + * @brief Get field ygyro from raw_imu message + * + * @return Angular speed around Y axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_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)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field zgyro from raw_imu message + * + * @return Angular speed around Z axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_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)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field xmag from raw_imu message + * + * @return X Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_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)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field ymag from raw_imu message + * + * @return Y Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_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)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field zmag from raw_imu message + * + * @return Z Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_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)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Decode a raw_imu message into a struct + * + * @param msg The message to decode + * @param raw_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu) +{ + raw_imu->usec = mavlink_msg_raw_imu_get_usec(msg); + raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg); + raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg); + raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg); + raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg); + raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg); + raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg); + raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg); + raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg); + raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_raw_pressure.h b/thirdParty/mavlink/include/common/mavlink_msg_raw_pressure.h new file mode 100644 index 0000000000000000000000000000000000000000..8346ac6286be8e1d7e7c04d704956a480c2ffd83 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_raw_pressure.h @@ -0,0 +1,190 @@ +// MESSAGE RAW_PRESSURE PACKING + +#define MAVLINK_MSG_ID_RAW_PRESSURE 29 + +typedef struct __mavlink_raw_pressure_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 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; + + + +/** + * @brief Pack a raw_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @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, 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_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); +} + +/** + * @brief Pack a raw_pressure 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @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, 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_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); +} + +/** + * @brief Encode a raw_pressure 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 raw_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) +{ + return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); +} + +/** + * @brief Send a raw_pressure message + * @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 (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, 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); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RAW_PRESSURE UNPACKING + +/** + * @brief Get field usec from raw_pressure message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_raw_pressure_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field press_abs from raw_pressure message + * + * @return Absolute pressure (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) +{ + 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 (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) +{ + 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 (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) +{ + 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 (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(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; +} + +/** + * @brief Decode a raw_pressure message into a struct + * + * @param msg The message to decode + * @param raw_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure) +{ + raw_pressure->usec = mavlink_msg_raw_pressure_get_usec(msg); + raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg); + raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg); + raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg); + raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_rc_channels_raw.h b/thirdParty/mavlink/include/common/mavlink_msg_rc_channels_raw.h new file mode 100644 index 0000000000000000000000000000000000000000..0443838bdcda0b7f5f41ffeb0080c0e0f5051608 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_rc_channels_raw.h @@ -0,0 +1,261 @@ +// MESSAGE RC_CHANNELS_RAW PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 + +typedef struct __mavlink_rc_channels_raw_t +{ + uint16_t chan1_raw; ///< RC channel 1 value, in microseconds + uint16_t chan2_raw; ///< RC channel 2 value, in microseconds + uint16_t chan3_raw; ///< RC channel 3 value, in microseconds + uint16_t chan4_raw; ///< RC channel 4 value, in microseconds + uint16_t chan5_raw; ///< RC channel 5 value, in microseconds + uint16_t chan6_raw; ///< RC channel 6 value, in microseconds + uint16_t chan7_raw; ///< RC channel 7 value, in microseconds + uint16_t chan8_raw; ///< RC channel 8 value, in microseconds + uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% + +} mavlink_rc_channels_raw_t; + + + +/** + * @brief Pack a rc_channels_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; + + i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds + i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds + i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds + i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds + i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds + i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds + i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds + i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds + i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100% + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a rc_channels_raw 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 chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; + + i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds + i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds + i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds + i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds + i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds + i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds + i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds + i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds + i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100% + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a rc_channels_raw 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 rc_channels_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) +{ + return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); +} + +/** + * @brief Send a rc_channels_raw message + * @param chan MAVLink channel to send the message + * + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ + mavlink_message_t msg; + mavlink_msg_rc_channels_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RC_CHANNELS_RAW UNPACKING + +/** + * @brief Get field chan1_raw from rc_channels_raw message + * + * @return RC channel 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(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 chan2_raw from rc_channels_raw message + * + * @return RC channel 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(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 chan3_raw from rc_channels_raw message + * + * @return RC channel 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(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 chan4_raw from rc_channels_raw message + * + * @return RC channel 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(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 chan5_raw from rc_channels_raw message + * + * @return RC channel 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(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; +} + +/** + * @brief Get field chan6_raw from rc_channels_raw message + * + * @return RC channel 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(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)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field chan7_raw from rc_channels_raw message + * + * @return RC channel 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(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)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field chan8_raw from rc_channels_raw message + * + * @return RC channel 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(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)+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)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field rssi from rc_channels_raw message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; +} + +/** + * @brief Decode a rc_channels_raw message into a struct + * + * @param msg The message to decode + * @param rc_channels_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw) +{ + rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg); + rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg); + rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg); + rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg); + rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg); + rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg); + rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg); + rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg); + rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_rc_channels_scaled.h b/thirdParty/mavlink/include/common/mavlink_msg_rc_channels_scaled.h new file mode 100644 index 0000000000000000000000000000000000000000..526482b4e0395acbd2bd2141fa923a5244249b4e --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_rc_channels_scaled.h @@ -0,0 +1,261 @@ +// MESSAGE RC_CHANNELS_SCALED PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 36 + +typedef struct __mavlink_rc_channels_scaled_t +{ + int16_t chan1_scaled; ///< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% + +} mavlink_rc_channels_scaled_t; + + + +/** + * @brief Pack a rc_channels_scaled 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 chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; + + i += put_int16_t_by_index(chan1_scaled, i, msg->payload); // RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan2_scaled, i, msg->payload); // RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan3_scaled, i, msg->payload); // RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan4_scaled, i, msg->payload); // RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan5_scaled, i, msg->payload); // RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan6_scaled, i, msg->payload); // RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan7_scaled, i, msg->payload); // RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan8_scaled, i, msg->payload); // RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100% + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a rc_channels_scaled 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 chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; + + i += put_int16_t_by_index(chan1_scaled, i, msg->payload); // RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan2_scaled, i, msg->payload); // RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan3_scaled, i, msg->payload); // RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan4_scaled, i, msg->payload); // RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan5_scaled, i, msg->payload); // RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan6_scaled, i, msg->payload); // RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan7_scaled, i, msg->payload); // RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_int16_t_by_index(chan8_scaled, i, msg->payload); // RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100% + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a rc_channels_scaled 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 rc_channels_scaled C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ + return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); +} + +/** + * @brief Send a rc_channels_scaled message + * @param chan MAVLink channel to send the message + * + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ + mavlink_message_t msg; + mavlink_msg_rc_channels_scaled_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RC_CHANNELS_SCALED UNPACKING + +/** + * @brief Get field chan1_scaled from rc_channels_scaled message + * + * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan2_scaled from rc_channels_scaled message + * + * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan3_scaled from rc_channels_scaled message + * + * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan4_scaled from rc_channels_scaled message + * + * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan5_scaled from rc_channels_scaled message + * + * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan6_scaled from rc_channels_scaled message + * + * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan7_scaled from rc_channels_scaled message + * + * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field chan8_scaled from rc_channels_scaled message + * + * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field rssi from rc_channels_scaled message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; +} + +/** + * @brief Decode a rc_channels_scaled message into a struct + * + * @param msg The message to decode + * @param rc_channels_scaled C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ + rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg); + rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg); + rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg); + rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg); + rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg); + rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg); + rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg); + rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg); + rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_request_data_stream.h b/thirdParty/mavlink/include/common/mavlink_msg_request_data_stream.h new file mode 100644 index 0000000000000000000000000000000000000000..f390e4e370c69002aac857b86f5dbec9bbc716f8 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_request_data_stream.h @@ -0,0 +1,172 @@ +// MESSAGE REQUEST_DATA_STREAM PACKING + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 + +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 Pack a request_data_stream message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param 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); +} + +/** + * @brief Pack a request_data_stream 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 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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t 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_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a request_data_stream 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_data_stream C-struct to read the message contents from + */ +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); +} + +/** + * @brief Send a request_data_stream message + * @param chan MAVLink channel to send the 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. + */ +#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_chan(mavlink_system.sysid, mavlink_system.compid, chan, &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]; +} + +/** + * @brief Decode a request_data_stream message into a struct + * + * @param msg The message to decode + * @param request_data_stream C-struct to decode the message contents into + */ +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); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_safety_allowed_area.h b/thirdParty/mavlink/include/common/mavlink_msg_safety_allowed_area.h new file mode 100644 index 0000000000000000000000000000000000000000..e1f9cc6b12d25925ca4cd15334d9e6174e702dde --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_safety_allowed_area.h @@ -0,0 +1,233 @@ +// MESSAGE SAFETY_ALLOWED_AREA PACKING + +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 54 + +typedef struct __mavlink_safety_allowed_area_t +{ + uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + float p1x; ///< x position 1 / Latitude 1 + float p1y; ///< y position 1 / Longitude 1 + float p1z; ///< z position 1 / Altitude 1 + float p2x; ///< x position 2 / Latitude 2 + float p2y; ///< y position 2 / Longitude 2 + float p2z; ///< z position 2 / Altitude 2 + +} mavlink_safety_allowed_area_t; + + + +/** + * @brief Pack a safety_allowed_area 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 frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; + + i += put_uint8_t_by_index(frame, i, msg->payload); // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + i += put_float_by_index(p1x, i, msg->payload); // x position 1 / Latitude 1 + i += put_float_by_index(p1y, i, msg->payload); // y position 1 / Longitude 1 + i += put_float_by_index(p1z, i, msg->payload); // z position 1 / Altitude 1 + i += put_float_by_index(p2x, i, msg->payload); // x position 2 / Latitude 2 + i += put_float_by_index(p2y, i, msg->payload); // y position 2 / Longitude 2 + i += put_float_by_index(p2z, i, msg->payload); // z position 2 / Altitude 2 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a safety_allowed_area 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 frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; + + i += put_uint8_t_by_index(frame, i, msg->payload); // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + i += put_float_by_index(p1x, i, msg->payload); // x position 1 / Latitude 1 + i += put_float_by_index(p1y, i, msg->payload); // y position 1 / Longitude 1 + i += put_float_by_index(p1z, i, msg->payload); // z position 1 / Altitude 1 + i += put_float_by_index(p2x, i, msg->payload); // x position 2 / Latitude 2 + i += put_float_by_index(p2y, i, msg->payload); // y position 2 / Longitude 2 + i += put_float_by_index(p2z, i, msg->payload); // z position 2 / Altitude 2 + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a safety_allowed_area 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 safety_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) +{ + return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); +} + +/** + * @brief Send a safety_allowed_area message + * @param chan MAVLink channel to send the message + * + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ + mavlink_message_t msg; + mavlink_msg_safety_allowed_area_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, frame, p1x, p1y, p1z, p2x, p2y, p2z); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SAFETY_ALLOWED_AREA UNPACKING + +/** + * @brief Get field frame from safety_allowed_area message + * + * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + */ +static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field p1x from safety_allowed_area message + * + * @return x position 1 / Latitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1x(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 p1y from safety_allowed_area message + * + * @return y position 1 / Longitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1y(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 p1z from safety_allowed_area message + * + * @return z position 1 / Altitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1z(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 p2x from safety_allowed_area message + * + * @return x position 2 / Latitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2x(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 p2y from safety_allowed_area message + * + * @return y position 2 / Longitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field p2z from safety_allowed_area message + * + * @return z position 2 / Altitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a safety_allowed_area message into a struct + * + * @param msg The message to decode + * @param safety_allowed_area C-struct to decode the message contents into + */ +static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area) +{ + safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg); + safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg); + safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg); + safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg); + safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg); + safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg); + safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_safety_set_allowed_area.h b/thirdParty/mavlink/include/common/mavlink_msg_safety_set_allowed_area.h new file mode 100644 index 0000000000000000000000000000000000000000..da571e8e7210dc711558278d0bce952f0cafc729 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_safety_set_allowed_area.h @@ -0,0 +1,267 @@ +// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING + +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 53 + +typedef struct __mavlink_safety_set_allowed_area_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + float p1x; ///< x position 1 / Latitude 1 + float p1y; ///< y position 1 / Longitude 1 + float p1z; ///< z position 1 / Altitude 1 + float p2x; ///< x position 2 / Latitude 2 + float p2y; ///< y position 2 / Longitude 2 + float p2z; ///< z position 2 / Altitude 2 + +} mavlink_safety_set_allowed_area_t; + + + +/** + * @brief Pack a safety_set_allowed_area message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; + + 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_uint8_t_by_index(frame, i, msg->payload); // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + i += put_float_by_index(p1x, i, msg->payload); // x position 1 / Latitude 1 + i += put_float_by_index(p1y, i, msg->payload); // y position 1 / Longitude 1 + i += put_float_by_index(p1z, i, msg->payload); // z position 1 / Altitude 1 + i += put_float_by_index(p2x, i, msg->payload); // x position 2 / Latitude 2 + i += put_float_by_index(p2y, i, msg->payload); // y position 2 / Longitude 2 + i += put_float_by_index(p2z, i, msg->payload); // z position 2 / Altitude 2 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a safety_set_allowed_area 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 System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; + + 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_uint8_t_by_index(frame, i, msg->payload); // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + i += put_float_by_index(p1x, i, msg->payload); // x position 1 / Latitude 1 + i += put_float_by_index(p1y, i, msg->payload); // y position 1 / Longitude 1 + i += put_float_by_index(p1z, i, msg->payload); // z position 1 / Altitude 1 + i += put_float_by_index(p2x, i, msg->payload); // x position 2 / Latitude 2 + i += put_float_by_index(p2y, i, msg->payload); // y position 2 / Longitude 2 + i += put_float_by_index(p2z, i, msg->payload); // z position 2 / Altitude 2 + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a safety_set_allowed_area 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 safety_set_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ + return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); +} + +/** + * @brief Send a safety_set_allowed_area message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ + mavlink_message_t msg; + mavlink_msg_safety_set_allowed_area_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING + +/** + * @brief Get field target_system from safety_set_allowed_area message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from safety_set_allowed_area message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field frame from safety_set_allowed_area message + * + * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field p1x from safety_set_allowed_area message + * + * @return x position 1 / Latitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field p1y from safety_set_allowed_area message + * + * @return y position 1 / Longitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field p1z from safety_set_allowed_area message + * + * @return z position 1 / Altitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field p2x from safety_set_allowed_area message + * + * @return x position 2 / Latitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field p2y from safety_set_allowed_area message + * + * @return y position 2 / Longitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field p2z from safety_set_allowed_area message + * + * @return z position 2 / Altitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a safety_set_allowed_area message into a struct + * + * @param msg The message to decode + * @param safety_set_allowed_area C-struct to decode the message contents into + */ +static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ + safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg); + safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg); + safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg); + safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg); + safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg); + safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg); + safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg); + safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg); + safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_scaled_imu.h b/thirdParty/mavlink/include/common/mavlink_msg_scaled_imu.h new file mode 100644 index 0000000000000000000000000000000000000000..77637286ff7a45adb6920079d79c2312a5c2758c --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_scaled_imu.h @@ -0,0 +1,290 @@ +// MESSAGE SCALED_IMU PACKING + +#define MAVLINK_MSG_ID_SCALED_IMU 26 + +typedef struct __mavlink_scaled_imu_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + int16_t xacc; ///< X acceleration (mg) + int16_t yacc; ///< Y acceleration (mg) + int16_t zacc; ///< Z acceleration (mg) + int16_t xgyro; ///< Angular speed around X axis (millirad /sec) + int16_t ygyro; ///< Angular speed around Y axis (millirad /sec) + int16_t zgyro; ///< Angular speed around Z axis (millirad /sec) + int16_t xmag; ///< X Magnetic field (milli tesla) + int16_t ymag; ///< Y Magnetic field (milli tesla) + int16_t zmag; ///< Z Magnetic field (milli tesla) + +} mavlink_scaled_imu_t; + + + +/** + * @brief Pack a scaled_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg) + i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg) + i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg) + i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (millirad /sec) + i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (millirad /sec) + i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (millirad /sec) + i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (milli tesla) + i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (milli tesla) + i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (milli tesla) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a scaled_imu 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg) + i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg) + i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg) + i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (millirad /sec) + i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (millirad /sec) + i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (millirad /sec) + i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (milli tesla) + i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (milli tesla) + i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (milli tesla) + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a scaled_imu 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 scaled_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) +{ + return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->usec, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); +} + +/** + * @brief Send a scaled_imu message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ + mavlink_message_t msg; + mavlink_msg_scaled_imu_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SCALED_IMU UNPACKING + +/** + * @brief Get field usec from scaled_imu message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_scaled_imu_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field xacc from scaled_imu message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg) +{ + 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 yacc from scaled_imu message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg) +{ + 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 zacc from scaled_imu message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg) +{ + 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 xgyro from scaled_imu message + * + * @return Angular speed around X axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg) +{ + generic_16bit r; + 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; +} + +/** + * @brief Get field ygyro from scaled_imu message + * + * @return Angular speed around Y axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_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)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field zgyro from scaled_imu message + * + * @return Angular speed around Z axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_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)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field xmag from scaled_imu message + * + * @return X Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_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)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field ymag from scaled_imu message + * + * @return Y Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_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)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field zmag from scaled_imu message + * + * @return Z Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_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)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Decode a scaled_imu message into a struct + * + * @param msg The message to decode + * @param scaled_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu) +{ + scaled_imu->usec = mavlink_msg_scaled_imu_get_usec(msg); + scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg); + scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg); + scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg); + scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg); + scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg); + scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg); + scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg); + scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg); + scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_scaled_pressure.h b/thirdParty/mavlink/include/common/mavlink_msg_scaled_pressure.h new file mode 100644 index 0000000000000000000000000000000000000000..08a9bedd37110bd1fb1717d2a8a2a510bf2306d3 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_scaled_pressure.h @@ -0,0 +1,174 @@ +// MESSAGE SCALED_PRESSURE PACKING + +#define MAVLINK_MSG_ID_SCALED_PRESSURE 38 + +typedef struct __mavlink_scaled_pressure_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + float press_abs; ///< Absolute pressure (hectopascal) + float press_diff; ///< Differential pressure 1 (hectopascal) + int16_t temperature; ///< Temperature measurement (0.01 degrees celsius) + +} mavlink_scaled_pressure_t; + + + +/** + * @brief Pack a scaled_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float press_abs, float press_diff, int16_t temperature) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SCALED_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_diff, i, msg->payload); // Differential pressure 1 (hectopascal) + i += put_int16_t_by_index(temperature, i, msg->payload); // Temperature measurement (0.01 degrees celsius) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a scaled_pressure 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 usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_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_diff, int16_t temperature) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SCALED_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_diff, i, msg->payload); // Differential pressure 1 (hectopascal) + i += put_int16_t_by_index(temperature, i, msg->payload); // Temperature measurement (0.01 degrees celsius) + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a scaled_pressure 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 scaled_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) +{ + return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->usec, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); +} + +/** + * @brief Send a scaled_pressure message + * @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_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint64_t usec, float press_abs, float press_diff, int16_t temperature) +{ + mavlink_message_t msg; + mavlink_msg_scaled_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff, temperature); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SCALED_PRESSURE UNPACKING + +/** + * @brief Get field usec from scaled_pressure message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_scaled_pressure_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field press_abs from scaled_pressure message + * + * @return Absolute pressure (hectopascal) + */ +static inline float mavlink_msg_scaled_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; +} + +/** + * @brief Get field press_diff from scaled_pressure message + * + * @return Differential pressure 1 (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure_get_press_diff(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; +} + +/** + * @brief Get field temperature from scaled_pressure message + * + * @return Temperature measurement (0.01 degrees celsius) + */ +static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + return (int16_t)r.s; +} + +/** + * @brief Decode a scaled_pressure message into a struct + * + * @param msg The message to decode + * @param scaled_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure) +{ + scaled_pressure->usec = mavlink_msg_scaled_pressure_get_usec(msg); + scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg); + scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg); + scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_servo_output_raw.h b/thirdParty/mavlink/include/common/mavlink_msg_servo_output_raw.h new file mode 100644 index 0000000000000000000000000000000000000000..751afcb80a3c3c7f8db4a559549efd4c389d91ae --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_servo_output_raw.h @@ -0,0 +1,244 @@ +// MESSAGE SERVO_OUTPUT_RAW PACKING + +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 37 + +typedef struct __mavlink_servo_output_raw_t +{ + uint16_t servo1_raw; ///< Servo output 1 value, in microseconds + uint16_t servo2_raw; ///< Servo output 2 value, in microseconds + uint16_t servo3_raw; ///< Servo output 3 value, in microseconds + uint16_t servo4_raw; ///< Servo output 4 value, in microseconds + uint16_t servo5_raw; ///< Servo output 5 value, in microseconds + uint16_t servo6_raw; ///< Servo output 6 value, in microseconds + uint16_t servo7_raw; ///< Servo output 7 value, in microseconds + uint16_t servo8_raw; ///< Servo output 8 value, in microseconds + +} mavlink_servo_output_raw_t; + + + +/** + * @brief Pack a servo_output_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; + + i += put_uint16_t_by_index(servo1_raw, i, msg->payload); // Servo output 1 value, in microseconds + i += put_uint16_t_by_index(servo2_raw, i, msg->payload); // Servo output 2 value, in microseconds + i += put_uint16_t_by_index(servo3_raw, i, msg->payload); // Servo output 3 value, in microseconds + i += put_uint16_t_by_index(servo4_raw, i, msg->payload); // Servo output 4 value, in microseconds + i += put_uint16_t_by_index(servo5_raw, i, msg->payload); // Servo output 5 value, in microseconds + i += put_uint16_t_by_index(servo6_raw, i, msg->payload); // Servo output 6 value, in microseconds + i += put_uint16_t_by_index(servo7_raw, i, msg->payload); // Servo output 7 value, in microseconds + i += put_uint16_t_by_index(servo8_raw, i, msg->payload); // Servo output 8 value, in microseconds + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a servo_output_raw 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 servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; + + i += put_uint16_t_by_index(servo1_raw, i, msg->payload); // Servo output 1 value, in microseconds + i += put_uint16_t_by_index(servo2_raw, i, msg->payload); // Servo output 2 value, in microseconds + i += put_uint16_t_by_index(servo3_raw, i, msg->payload); // Servo output 3 value, in microseconds + i += put_uint16_t_by_index(servo4_raw, i, msg->payload); // Servo output 4 value, in microseconds + i += put_uint16_t_by_index(servo5_raw, i, msg->payload); // Servo output 5 value, in microseconds + i += put_uint16_t_by_index(servo6_raw, i, msg->payload); // Servo output 6 value, in microseconds + i += put_uint16_t_by_index(servo7_raw, i, msg->payload); // Servo output 7 value, in microseconds + i += put_uint16_t_by_index(servo8_raw, i, msg->payload); // Servo output 8 value, in microseconds + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a servo_output_raw 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 servo_output_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) +{ + return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); +} + +/** + * @brief Send a servo_output_raw message + * @param chan MAVLink channel to send the message + * + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ + mavlink_message_t msg; + mavlink_msg_servo_output_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SERVO_OUTPUT_RAW UNPACKING + +/** + * @brief Get field servo1_raw from servo_output_raw message + * + * @return Servo output 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(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 servo2_raw from servo_output_raw message + * + * @return Servo output 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(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 servo3_raw from servo_output_raw message + * + * @return Servo output 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(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 servo4_raw from servo_output_raw message + * + * @return Servo output 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(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 servo5_raw from servo_output_raw message + * + * @return Servo output 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(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; +} + +/** + * @brief Get field servo6_raw from servo_output_raw message + * + * @return Servo output 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(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)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field servo7_raw from servo_output_raw message + * + * @return Servo output 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(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)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field servo8_raw from servo_output_raw message + * + * @return Servo output 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(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)+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)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Decode a servo_output_raw message into a struct + * + * @param msg The message to decode + * @param servo_output_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw) +{ + servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg); + servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg); + servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg); + servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg); + servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg); + servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg); + servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg); + servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_set_altitude.h b/thirdParty/mavlink/include/common/mavlink_msg_set_altitude.h new file mode 100644 index 0000000000000000000000000000000000000000..775db90e343bb67430894f9281f5ad063761f7dd --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_set_altitude.h @@ -0,0 +1,123 @@ +// MESSAGE SET_ALTITUDE PACKING + +#define MAVLINK_MSG_ID_SET_ALTITUDE 65 + +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 Pack a set_altitude 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 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); +} + +/** + * @brief Pack a set_altitude 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 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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 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_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a set_altitude 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 set_altitude C-struct to read the message contents from + */ +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); +} + +/** + * @brief Send a set_altitude message + * @param chan MAVLink channel to send the message + * + * @param target The system setting the altitude + * @param mode The new altitude in meters + */ +#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_chan(mavlink_system.sysid, mavlink_system.compid, chan, &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; +} + +/** + * @brief Decode a set_altitude message into a struct + * + * @param msg The message to decode + * @param set_altitude C-struct to decode the message contents into + */ +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); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_set_mode.h b/thirdParty/mavlink/include/common/mavlink_msg_set_mode.h new file mode 100644 index 0000000000000000000000000000000000000000..efeea6509f070903e55a2728f123cce48810ae73 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_set_mode.h @@ -0,0 +1,118 @@ +// MESSAGE SET_MODE PACKING + +#define MAVLINK_MSG_ID_SET_MODE 11 + +typedef struct __mavlink_set_mode_t +{ + uint8_t target; ///< The system setting the mode + uint8_t mode; ///< The new mode + +} mavlink_set_mode_t; + + + +/** + * @brief Pack a set_mode 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 mode + * @param mode The new mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t mode) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_MODE; + + i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode + i += put_uint8_t_by_index(mode, i, msg->payload); // The new mode + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a set_mode 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 mode + * @param mode The new mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t mode) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_MODE; + + i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode + i += put_uint8_t_by_index(mode, i, msg->payload); // The new mode + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a set_mode 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 set_mode C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) +{ + return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target, set_mode->mode); +} + +/** + * @brief Send a set_mode message + * @param chan MAVLink channel to send the message + * + * @param target The system setting the mode + * @param mode The new mode + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t mode) +{ + mavlink_message_t msg; + mavlink_msg_set_mode_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, mode); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SET_MODE UNPACKING + +/** + * @brief Get field target from set_mode message + * + * @return The system setting the mode + */ +static inline uint8_t mavlink_msg_set_mode_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field mode from set_mode message + * + * @return The new mode + */ +static inline uint8_t mavlink_msg_set_mode_get_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a set_mode message into a struct + * + * @param msg The message to decode + * @param set_mode C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode) +{ + set_mode->target = mavlink_msg_set_mode_get_target(msg); + set_mode->mode = mavlink_msg_set_mode_get_mode(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_set_nav_mode.h b/thirdParty/mavlink/include/common/mavlink_msg_set_nav_mode.h new file mode 100644 index 0000000000000000000000000000000000000000..fe514b2ea53cebb352fc8747e8477d4797e23713 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_set_nav_mode.h @@ -0,0 +1,118 @@ +// MESSAGE SET_NAV_MODE PACKING + +#define MAVLINK_MSG_ID_SET_NAV_MODE 12 + +typedef struct __mavlink_set_nav_mode_t +{ + uint8_t target; ///< The system setting the mode + uint8_t nav_mode; ///< The new navigation mode + +} mavlink_set_nav_mode_t; + + + +/** + * @brief Pack a set_nav_mode 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 mode + * @param nav_mode The new navigation mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_nav_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t nav_mode) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE; + + i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode + i += put_uint8_t_by_index(nav_mode, i, msg->payload); // The new navigation mode + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a set_nav_mode 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 mode + * @param nav_mode The new navigation mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_nav_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t nav_mode) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE; + + i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode + i += put_uint8_t_by_index(nav_mode, i, msg->payload); // The new navigation mode + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a set_nav_mode 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 set_nav_mode C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_nav_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_nav_mode_t* set_nav_mode) +{ + return mavlink_msg_set_nav_mode_pack(system_id, component_id, msg, set_nav_mode->target, set_nav_mode->nav_mode); +} + +/** + * @brief Send a set_nav_mode message + * @param chan MAVLink channel to send the message + * + * @param target The system setting the mode + * @param nav_mode The new navigation mode + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_nav_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t nav_mode) +{ + mavlink_message_t msg; + mavlink_msg_set_nav_mode_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, nav_mode); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SET_NAV_MODE UNPACKING + +/** + * @brief Get field target from set_nav_mode message + * + * @return The system setting the mode + */ +static inline uint8_t mavlink_msg_set_nav_mode_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field nav_mode from set_nav_mode message + * + * @return The new navigation mode + */ +static inline uint8_t mavlink_msg_set_nav_mode_get_nav_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a set_nav_mode message into a struct + * + * @param msg The message to decode + * @param set_nav_mode C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_nav_mode_decode(const mavlink_message_t* msg, mavlink_set_nav_mode_t* set_nav_mode) +{ + set_nav_mode->target = mavlink_msg_set_nav_mode_get_target(msg); + set_nav_mode->nav_mode = mavlink_msg_set_nav_mode_get_nav_mode(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_state_correction.h b/thirdParty/mavlink/include/common/mavlink_msg_state_correction.h new file mode 100644 index 0000000000000000000000000000000000000000..c4c6b5abc9e36a7d3bbca3e4b3bb7610c30410c1 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_state_correction.h @@ -0,0 +1,282 @@ +// MESSAGE STATE_CORRECTION PACKING + +#define MAVLINK_MSG_ID_STATE_CORRECTION 64 + +typedef struct __mavlink_state_correction_t +{ + float xErr; ///< x position error + float yErr; ///< y position error + float zErr; ///< z position error + float rollErr; ///< roll error (radians) + float pitchErr; ///< pitch error (radians) + float yawErr; ///< yaw error (radians) + float vxErr; ///< x velocity + float vyErr; ///< y velocity + float vzErr; ///< z velocity + +} mavlink_state_correction_t; + + + +/** + * @brief Pack a state_correction 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 xErr x position error + * @param yErr y position error + * @param zErr z position error + * @param rollErr roll error (radians) + * @param pitchErr pitch error (radians) + * @param yawErr yaw error (radians) + * @param vxErr x velocity + * @param vyErr y velocity + * @param vzErr z velocity + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; + + i += put_float_by_index(xErr, i, msg->payload); // x position error + i += put_float_by_index(yErr, i, msg->payload); // y position error + i += put_float_by_index(zErr, i, msg->payload); // z position error + i += put_float_by_index(rollErr, i, msg->payload); // roll error (radians) + i += put_float_by_index(pitchErr, i, msg->payload); // pitch error (radians) + i += put_float_by_index(yawErr, i, msg->payload); // yaw error (radians) + i += put_float_by_index(vxErr, i, msg->payload); // x velocity + i += put_float_by_index(vyErr, i, msg->payload); // y velocity + i += put_float_by_index(vzErr, i, msg->payload); // z velocity + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a state_correction 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 xErr x position error + * @param yErr y position error + * @param zErr z position error + * @param rollErr roll error (radians) + * @param pitchErr pitch error (radians) + * @param yawErr yaw error (radians) + * @param vxErr x velocity + * @param vyErr y velocity + * @param vzErr z velocity + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; + + i += put_float_by_index(xErr, i, msg->payload); // x position error + i += put_float_by_index(yErr, i, msg->payload); // y position error + i += put_float_by_index(zErr, i, msg->payload); // z position error + i += put_float_by_index(rollErr, i, msg->payload); // roll error (radians) + i += put_float_by_index(pitchErr, i, msg->payload); // pitch error (radians) + i += put_float_by_index(yawErr, i, msg->payload); // yaw error (radians) + i += put_float_by_index(vxErr, i, msg->payload); // x velocity + i += put_float_by_index(vyErr, i, msg->payload); // y velocity + i += put_float_by_index(vzErr, i, msg->payload); // z velocity + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a state_correction 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 state_correction C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction) +{ + return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr); +} + +/** + * @brief Send a state_correction message + * @param chan MAVLink channel to send the message + * + * @param xErr x position error + * @param yErr y position error + * @param zErr z position error + * @param rollErr roll error (radians) + * @param pitchErr pitch error (radians) + * @param yawErr yaw error (radians) + * @param vxErr x velocity + * @param vyErr y velocity + * @param vzErr z velocity + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) +{ + mavlink_message_t msg; + mavlink_msg_state_correction_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE STATE_CORRECTION UNPACKING + +/** + * @brief Get field xErr from state_correction message + * + * @return x position error + */ +static inline float mavlink_msg_state_correction_get_xErr(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 yErr from state_correction message + * + * @return y position error + */ +static inline float mavlink_msg_state_correction_get_yErr(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 zErr from state_correction message + * + * @return z position error + */ +static inline float mavlink_msg_state_correction_get_zErr(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 rollErr from state_correction message + * + * @return roll error (radians) + */ +static inline float mavlink_msg_state_correction_get_rollErr(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 pitchErr from state_correction message + * + * @return pitch error (radians) + */ +static inline float mavlink_msg_state_correction_get_pitchErr(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 yawErr from state_correction message + * + * @return yaw error (radians) + */ +static inline float mavlink_msg_state_correction_get_yawErr(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 vxErr from state_correction message + * + * @return x velocity + */ +static inline float mavlink_msg_state_correction_get_vxErr(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 vyErr from state_correction message + * + * @return y velocity + */ +static inline float mavlink_msg_state_correction_get_vyErr(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 vzErr from state_correction message + * + * @return z velocity + */ +static inline float mavlink_msg_state_correction_get_vzErr(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; +} + +/** + * @brief Decode a state_correction message into a struct + * + * @param msg The message to decode + * @param state_correction C-struct to decode the message contents into + */ +static inline void mavlink_msg_state_correction_decode(const mavlink_message_t* msg, mavlink_state_correction_t* state_correction) +{ + state_correction->xErr = mavlink_msg_state_correction_get_xErr(msg); + state_correction->yErr = mavlink_msg_state_correction_get_yErr(msg); + state_correction->zErr = mavlink_msg_state_correction_get_zErr(msg); + state_correction->rollErr = mavlink_msg_state_correction_get_rollErr(msg); + state_correction->pitchErr = mavlink_msg_state_correction_get_pitchErr(msg); + state_correction->yawErr = mavlink_msg_state_correction_get_yawErr(msg); + state_correction->vxErr = mavlink_msg_state_correction_get_vxErr(msg); + state_correction->vyErr = mavlink_msg_state_correction_get_vyErr(msg); + state_correction->vzErr = mavlink_msg_state_correction_get_vzErr(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_statustext.h b/thirdParty/mavlink/include/common/mavlink_msg_statustext.h new file mode 100644 index 0000000000000000000000000000000000000000..681b659c4d2c75aa1c27de58bdcb0a9efadcab70 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_statustext.h @@ -0,0 +1,121 @@ +// MESSAGE STATUSTEXT PACKING + +#define MAVLINK_MSG_ID_STATUSTEXT 254 + +typedef struct __mavlink_statustext_t +{ + uint8_t severity; ///< Severity of status, 0 = info message, 255 = critical fault + int8_t text[50]; ///< Status text message, without null termination character + +} mavlink_statustext_t; + +#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50 + + +/** + * @brief Pack a statustext 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 severity Severity of status, 0 = info message, 255 = critical fault + * @param text Status text message, without null termination character + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t severity, const int8_t* text) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; + + i += put_uint8_t_by_index(severity, i, msg->payload); // Severity of status, 0 = info message, 255 = critical fault + i += put_array_by_index((const int8_t*)text, sizeof(int8_t)*50, i, msg->payload); // Status text message, without null termination character + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a statustext 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 severity Severity of status, 0 = info message, 255 = critical fault + * @param text Status text message, without null termination character + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t severity, const int8_t* text) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; + + i += put_uint8_t_by_index(severity, i, msg->payload); // Severity of status, 0 = info message, 255 = critical fault + i += put_array_by_index((const int8_t*)text, sizeof(int8_t)*50, i, msg->payload); // Status text message, without null termination character + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a statustext 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 statustext C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext) +{ + return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text); +} + +/** + * @brief Send a statustext message + * @param chan MAVLink channel to send the message + * + * @param severity Severity of status, 0 = info message, 255 = critical fault + * @param text Status text message, without null termination character + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const int8_t* text) +{ + mavlink_message_t msg; + mavlink_msg_statustext_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, severity, text); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE STATUSTEXT UNPACKING + +/** + * @brief Get field severity from statustext message + * + * @return Severity of status, 0 = info message, 255 = critical fault + */ +static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field text from statustext message + * + * @return Status text message, without null termination character + */ +static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t), sizeof(int8_t)*50); + return sizeof(int8_t)*50; +} + +/** + * @brief Decode a statustext message into a struct + * + * @param msg The message to decode + * @param statustext C-struct to decode the message contents into + */ +static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext) +{ + statustext->severity = mavlink_msg_statustext_get_severity(msg); + mavlink_msg_statustext_get_text(msg, statustext->text); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_sys_status.h b/thirdParty/mavlink/include/common/mavlink_msg_sys_status.h new file mode 100644 index 0000000000000000000000000000000000000000..ef83d844813b07c3a0692b704e232894e58e1510 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_sys_status.h @@ -0,0 +1,215 @@ +// MESSAGE SYS_STATUS PACKING + +#define MAVLINK_MSG_ID_SYS_STATUS 34 + +typedef struct __mavlink_sys_status_t +{ + uint8_t mode; ///< System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + uint8_t nav_mode; ///< Navigation mode, see MAV_NAV_MODE ENUM + uint8_t status; ///< System status flag, see MAV_STATUS ENUM + uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + uint16_t vbat; ///< Battery voltage, in millivolts (1 = 1 millivolt) + uint16_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 1000) + uint16_t packet_drop; ///< Dropped packets (packets that were corrupted on reception on the MAV) + +} mavlink_sys_status_t; + + + +/** + * @brief Pack a sys_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM + * @param status System status flag, see MAV_STATUS ENUM + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param vbat Battery voltage, in millivolts (1 = 1 millivolt) + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000) + * @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint16_t battery_remaining, uint16_t packet_drop) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; + + i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see MAV_NAV_MODE ENUM + i += put_uint8_t_by_index(status, i, msg->payload); // System status flag, see MAV_STATUS ENUM + i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage, in millivolts (1 = 1 millivolt) + i += put_uint16_t_by_index(battery_remaining, i, msg->payload); // Remaining battery energy: (0%: 0, 100%: 1000) + i += put_uint16_t_by_index(packet_drop, i, msg->payload); // Dropped packets (packets that were corrupted on reception on the MAV) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a sys_status 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 mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM + * @param status System status flag, see MAV_STATUS ENUM + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param vbat Battery voltage, in millivolts (1 = 1 millivolt) + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000) + * @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint16_t battery_remaining, uint16_t packet_drop) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; + + i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see MAV_NAV_MODE ENUM + i += put_uint8_t_by_index(status, i, msg->payload); // System status flag, see MAV_STATUS ENUM + i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage, in millivolts (1 = 1 millivolt) + i += put_uint16_t_by_index(battery_remaining, i, msg->payload); // Remaining battery energy: (0%: 0, 100%: 1000) + i += put_uint16_t_by_index(packet_drop, i, msg->payload); // Dropped packets (packets that were corrupted on reception on the MAV) + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a sys_status 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 sys_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) +{ + return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->mode, sys_status->nav_mode, sys_status->status, sys_status->load, sys_status->vbat, sys_status->battery_remaining, sys_status->packet_drop); +} + +/** + * @brief Send a sys_status message + * @param chan MAVLink channel to send the message + * + * @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM + * @param status System status flag, see MAV_STATUS ENUM + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param vbat Battery voltage, in millivolts (1 = 1 millivolt) + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000) + * @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint16_t battery_remaining, uint16_t packet_drop) +{ + mavlink_message_t msg; + mavlink_msg_sys_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SYS_STATUS UNPACKING + +/** + * @brief Get field mode from sys_status message + * + * @return System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + */ +static inline uint8_t mavlink_msg_sys_status_get_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field nav_mode from sys_status message + * + * @return Navigation mode, see MAV_NAV_MODE ENUM + */ +static inline uint8_t mavlink_msg_sys_status_get_nav_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field status from sys_status message + * + * @return System status flag, see MAV_STATUS ENUM + */ +static inline uint8_t mavlink_msg_sys_status_get_status(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field load from sys_status message + * + * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + */ +static inline uint16_t mavlink_msg_sys_status_get_load(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 vbat from sys_status message + * + * @return Battery voltage, in millivolts (1 = 1 millivolt) + */ +static inline uint16_t mavlink_msg_sys_status_get_vbat(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field battery_remaining from sys_status message + * + * @return Remaining battery energy: (0%: 0, 100%: 1000) + */ +static inline uint16_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field packet_drop from sys_status message + * + * @return Dropped packets (packets that were corrupted on reception on the MAV) + */ +static inline uint16_t mavlink_msg_sys_status_get_packet_drop(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Decode a sys_status message into a struct + * + * @param msg The message to decode + * @param sys_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status) +{ + sys_status->mode = mavlink_msg_sys_status_get_mode(msg); + sys_status->nav_mode = mavlink_msg_sys_status_get_nav_mode(msg); + sys_status->status = mavlink_msg_sys_status_get_status(msg); + sys_status->load = mavlink_msg_sys_status_get_load(msg); + sys_status->vbat = mavlink_msg_sys_status_get_vbat(msg); + sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg); + sys_status->packet_drop = mavlink_msg_sys_status_get_packet_drop(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_system_time.h b/thirdParty/mavlink/include/common/mavlink_msg_system_time.h new file mode 100644 index 0000000000000000000000000000000000000000..d293f025bfc5937c253e1e78747c61720b88f436 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_system_time.h @@ -0,0 +1,110 @@ +// MESSAGE SYSTEM_TIME PACKING + +#define MAVLINK_MSG_ID_SYSTEM_TIME 2 + +typedef struct __mavlink_system_time_t +{ + uint64_t time_usec; ///< Timestamp of the master clock in microseconds since UNIX epoch. + +} mavlink_system_time_t; + + + +/** + * @brief Pack a system_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 time_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t time_usec) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; + + i += put_uint64_t_by_index(time_usec, i, msg->payload); // Timestamp of the master clock in microseconds since UNIX epoch. + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a system_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 time_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t time_usec) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; + + i += put_uint64_t_by_index(time_usec, i, msg->payload); // Timestamp of the master clock in microseconds since UNIX epoch. + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a system_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 system_time C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time) +{ + return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_usec); +} + +/** + * @brief Send a system_time message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp of the master clock in microseconds since UNIX epoch. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_usec) +{ + mavlink_message_t msg; + mavlink_msg_system_time_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time_usec); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SYSTEM_TIME UNPACKING + +/** + * @brief Get field time_usec from system_time message + * + * @return Timestamp of the master clock in microseconds since UNIX epoch. + */ +static inline uint64_t mavlink_msg_system_time_get_time_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Decode a system_time message into a struct + * + * @param msg The message to decode + * @param system_time C-struct to decode the message contents into + */ +static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time) +{ + system_time->time_usec = mavlink_msg_system_time_get_time_usec(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_system_time_utc.h b/thirdParty/mavlink/include/common/mavlink_msg_system_time_utc.h new file mode 100644 index 0000000000000000000000000000000000000000..75c25f1ced937bd7d13bfdfa91f07bf7601200f5 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_system_time_utc.h @@ -0,0 +1,128 @@ +// MESSAGE SYSTEM_TIME_UTC PACKING + +#define MAVLINK_MSG_ID_SYSTEM_TIME_UTC 4 + +typedef struct __mavlink_system_time_utc_t +{ + uint32_t utc_date; ///< GPS UTC date ddmmyy + uint32_t utc_time; ///< GPS UTC time hhmmss + +} mavlink_system_time_utc_t; + + + +/** + * @brief Pack a system_time_utc 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 utc_date GPS UTC date ddmmyy + * @param utc_time GPS UTC time hhmmss + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_utc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t utc_date, uint32_t utc_time) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC; + + i += put_uint32_t_by_index(utc_date, i, msg->payload); // GPS UTC date ddmmyy + i += put_uint32_t_by_index(utc_time, i, msg->payload); // GPS UTC time hhmmss + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a system_time_utc 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 utc_date GPS UTC date ddmmyy + * @param utc_time GPS UTC time hhmmss + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_utc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t utc_date, uint32_t utc_time) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC; + + i += put_uint32_t_by_index(utc_date, i, msg->payload); // GPS UTC date ddmmyy + i += put_uint32_t_by_index(utc_time, i, msg->payload); // GPS UTC time hhmmss + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a system_time_utc 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 system_time_utc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_system_time_utc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_utc_t* system_time_utc) +{ + return mavlink_msg_system_time_utc_pack(system_id, component_id, msg, system_time_utc->utc_date, system_time_utc->utc_time); +} + +/** + * @brief Send a system_time_utc message + * @param chan MAVLink channel to send the message + * + * @param utc_date GPS UTC date ddmmyy + * @param utc_time GPS UTC time hhmmss + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_system_time_utc_send(mavlink_channel_t chan, uint32_t utc_date, uint32_t utc_time) +{ + mavlink_message_t msg; + mavlink_msg_system_time_utc_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, utc_date, utc_time); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SYSTEM_TIME_UTC UNPACKING + +/** + * @brief Get field utc_date from system_time_utc message + * + * @return GPS UTC date ddmmyy + */ +static inline uint32_t mavlink_msg_system_time_utc_get_utc_date(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 (uint32_t)r.i; +} + +/** + * @brief Get field utc_time from system_time_utc message + * + * @return GPS UTC time hhmmss + */ +static inline uint32_t mavlink_msg_system_time_utc_get_utc_time(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint32_t))[3]; + return (uint32_t)r.i; +} + +/** + * @brief Decode a system_time_utc message into a struct + * + * @param msg The message to decode + * @param system_time_utc C-struct to decode the message contents into + */ +static inline void mavlink_msg_system_time_utc_decode(const mavlink_message_t* msg, mavlink_system_time_utc_t* system_time_utc) +{ + system_time_utc->utc_date = mavlink_msg_system_time_utc_get_utc_date(msg); + system_time_utc->utc_time = mavlink_msg_system_time_utc_get_utc_time(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_vfr_hud.h b/thirdParty/mavlink/include/common/mavlink_msg_vfr_hud.h new file mode 100644 index 0000000000000000000000000000000000000000..9f55bdfa70f7b3f754db24eda1c73f720e52daa3 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_vfr_hud.h @@ -0,0 +1,212 @@ +// MESSAGE VFR_HUD PACKING + +#define MAVLINK_MSG_ID_VFR_HUD 74 + +typedef struct __mavlink_vfr_hud_t +{ + float airspeed; ///< Current airspeed in m/s + float groundspeed; ///< Current ground speed in m/s + int16_t heading; ///< Current heading in degrees, in compass units (0..360, 0=north) + uint16_t throttle; ///< Current throttle setting in integer percent, 0 to 100 + float alt; ///< Current altitude (MSL), in meters + float climb; ///< Current climb rate in meters/second + +} mavlink_vfr_hud_t; + + + +/** + * @brief Pack a vfr_hud 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 airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_VFR_HUD; + + i += put_float_by_index(airspeed, i, msg->payload); // Current airspeed in m/s + i += put_float_by_index(groundspeed, i, msg->payload); // Current ground speed in m/s + i += put_int16_t_by_index(heading, i, msg->payload); // Current heading in degrees, in compass units (0..360, 0=north) + i += put_uint16_t_by_index(throttle, i, msg->payload); // Current throttle setting in integer percent, 0 to 100 + i += put_float_by_index(alt, i, msg->payload); // Current altitude (MSL), in meters + i += put_float_by_index(climb, i, msg->payload); // Current climb rate in meters/second + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a vfr_hud 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 airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_VFR_HUD; + + i += put_float_by_index(airspeed, i, msg->payload); // Current airspeed in m/s + i += put_float_by_index(groundspeed, i, msg->payload); // Current ground speed in m/s + i += put_int16_t_by_index(heading, i, msg->payload); // Current heading in degrees, in compass units (0..360, 0=north) + i += put_uint16_t_by_index(throttle, i, msg->payload); // Current throttle setting in integer percent, 0 to 100 + i += put_float_by_index(alt, i, msg->payload); // Current altitude (MSL), in meters + i += put_float_by_index(climb, i, msg->payload); // Current climb rate in meters/second + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a vfr_hud 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 vfr_hud C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) +{ + return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); +} + +/** + * @brief Send a vfr_hud message + * @param chan MAVLink channel to send the message + * + * @param airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ + mavlink_message_t msg; + mavlink_msg_vfr_hud_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, airspeed, groundspeed, heading, throttle, alt, climb); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE VFR_HUD UNPACKING + +/** + * @brief Get field airspeed from vfr_hud message + * + * @return Current airspeed in m/s + */ +static inline float mavlink_msg_vfr_hud_get_airspeed(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 groundspeed from vfr_hud message + * + * @return Current ground speed in m/s + */ +static inline float mavlink_msg_vfr_hud_get_groundspeed(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 heading from vfr_hud message + * + * @return Current heading in degrees, in compass units (0..360, 0=north) + */ +static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[0]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field throttle from vfr_hud message + * + * @return Current throttle setting in integer percent, 0 to 100 + */ +static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field alt from vfr_hud message + * + * @return Current altitude (MSL), in meters + */ +static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field climb from vfr_hud message + * + * @return Current climb rate in meters/second + */ +static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a vfr_hud message into a struct + * + * @param msg The message to decode + * @param vfr_hud C-struct to decode the message contents into + */ +static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud) +{ + vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg); + vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg); + vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg); + vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg); + vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg); + vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_waypoint.h b/thirdParty/mavlink/include/common/mavlink_msg_waypoint.h new file mode 100644 index 0000000000000000000000000000000000000000..ab1c5f836a0b44b4e7139c486eec860dc6b6c90f --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_waypoint.h @@ -0,0 +1,360 @@ +// MESSAGE WAYPOINT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT 39 + +typedef struct __mavlink_waypoint_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint16_t seq; ///< Sequence + uint8_t frame; ///< The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + uint8_t command; ///< The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + uint8_t current; ///< false:0, true:1 + uint8_t autocontinue; ///< autocontinue to next wp + float param1; ///< PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + float param2; ///< PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + float param3; ///< PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + float param4; ///< PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + float x; ///< PARAM5 / local: x position, global: latitude + float y; ///< PARAM6 / y position: global: longitude + float z; ///< PARAM7 / z position: global: altitude + +} mavlink_waypoint_t; + + + +/** + * @brief Pack a waypoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT; + + 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_uint16_t_by_index(seq, i, msg->payload); // Sequence + i += put_uint8_t_by_index(frame, i, msg->payload); // The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + i += put_uint8_t_by_index(command, i, msg->payload); // The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + i += put_uint8_t_by_index(current, i, msg->payload); // false:0, true:1 + i += put_uint8_t_by_index(autocontinue, i, msg->payload); // autocontinue to next wp + i += put_float_by_index(param1, i, msg->payload); // PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + i += put_float_by_index(param2, i, msg->payload); // PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + i += put_float_by_index(param3, i, msg->payload); // PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + i += put_float_by_index(param4, i, msg->payload); // PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: latitude + i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: longitude + i += put_float_by_index(z, i, msg->payload); // PARAM7 / z position: global: altitude + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a waypoint 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 System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_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 seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT; + + 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_uint16_t_by_index(seq, i, msg->payload); // Sequence + i += put_uint8_t_by_index(frame, i, msg->payload); // The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + i += put_uint8_t_by_index(command, i, msg->payload); // The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + i += put_uint8_t_by_index(current, i, msg->payload); // false:0, true:1 + i += put_uint8_t_by_index(autocontinue, i, msg->payload); // autocontinue to next wp + i += put_float_by_index(param1, i, msg->payload); // PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + i += put_float_by_index(param2, i, msg->payload); // PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + i += put_float_by_index(param3, i, msg->payload); // PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + i += put_float_by_index(param4, i, msg->payload); // PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + i += put_float_by_index(x, i, msg->payload); // PARAM5 / local: x position, global: latitude + i += put_float_by_index(y, i, msg->payload); // PARAM6 / y position: global: longitude + i += put_float_by_index(z, i, msg->payload); // PARAM7 / z position: global: altitude + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a waypoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_t* waypoint) +{ + return mavlink_msg_waypoint_pack(system_id, component_id, msg, waypoint->target_system, waypoint->target_component, waypoint->seq, waypoint->frame, waypoint->command, waypoint->current, waypoint->autocontinue, waypoint->param1, waypoint->param2, waypoint->param3, waypoint->param4, waypoint->x, waypoint->y, waypoint->z); +} + +/** + * @brief Send a waypoint message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT UNPACKING + +/** + * @brief Get field target_system from waypoint message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field seq from waypoint message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_get_seq(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 Get field frame from waypoint message + * + * @return The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + */ +static inline uint8_t mavlink_msg_waypoint_get_frame(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; +} + +/** + * @brief Get field command from waypoint message + * + * @return The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + */ +static inline uint8_t mavlink_msg_waypoint_get_command(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field current from waypoint message + * + * @return false:0, true:1 + */ +static inline uint8_t mavlink_msg_waypoint_get_current(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field autocontinue from waypoint message + * + * @return autocontinue to next wp + */ +static inline uint8_t mavlink_msg_waypoint_get_autocontinue(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field param1 from waypoint message + * + * @return PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + */ +static inline float mavlink_msg_waypoint_get_param1(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field param2 from waypoint message + * + * @return PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + */ +static inline float mavlink_msg_waypoint_get_param2(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field param3 from waypoint message + * + * @return PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + */ +static inline float mavlink_msg_waypoint_get_param3(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field param4 from waypoint message + * + * @return PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + */ +static inline float mavlink_msg_waypoint_get_param4(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field x from waypoint message + * + * @return PARAM5 / local: x position, global: latitude + */ +static inline float mavlink_msg_waypoint_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from waypoint message + * + * @return PARAM6 / y position: global: longitude + */ +static inline float mavlink_msg_waypoint_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from waypoint message + * + * @return PARAM7 / z position: global: altitude + */ +static inline float mavlink_msg_waypoint_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a waypoint message into a struct + * + * @param msg The message to decode + * @param waypoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_decode(const mavlink_message_t* msg, mavlink_waypoint_t* waypoint) +{ + waypoint->target_system = mavlink_msg_waypoint_get_target_system(msg); + waypoint->target_component = mavlink_msg_waypoint_get_target_component(msg); + waypoint->seq = mavlink_msg_waypoint_get_seq(msg); + waypoint->frame = mavlink_msg_waypoint_get_frame(msg); + waypoint->command = mavlink_msg_waypoint_get_command(msg); + waypoint->current = mavlink_msg_waypoint_get_current(msg); + waypoint->autocontinue = mavlink_msg_waypoint_get_autocontinue(msg); + waypoint->param1 = mavlink_msg_waypoint_get_param1(msg); + waypoint->param2 = mavlink_msg_waypoint_get_param2(msg); + waypoint->param3 = mavlink_msg_waypoint_get_param3(msg); + waypoint->param4 = mavlink_msg_waypoint_get_param4(msg); + waypoint->x = mavlink_msg_waypoint_get_x(msg); + waypoint->y = mavlink_msg_waypoint_get_y(msg); + waypoint->z = mavlink_msg_waypoint_get_z(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_waypoint_ack.h b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_ack.h new file mode 100644 index 0000000000000000000000000000000000000000..d994eaf49a76a8a6b226311052dbf8451c9e4493 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_ack.h @@ -0,0 +1,135 @@ +// MESSAGE WAYPOINT_ACK PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_ACK 47 + +typedef struct __mavlink_waypoint_ack_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t type; ///< 0: OK, 1: Error + +} mavlink_waypoint_ack_t; + + + +/** + * @brief Pack a waypoint_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param type 0: OK, 1: Error + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t type) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK; + + 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_uint8_t_by_index(type, i, msg->payload); // 0: OK, 1: Error + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a waypoint_ack 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 System ID + * @param target_component Component ID + * @param type 0: OK, 1: Error + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint8_t type) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK; + + 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_uint8_t_by_index(type, i, msg->payload); // 0: OK, 1: Error + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a waypoint_ack struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_ack_t* waypoint_ack) +{ + return mavlink_msg_waypoint_ack_pack(system_id, component_id, msg, waypoint_ack->target_system, waypoint_ack->target_component, waypoint_ack->type); +} + +/** + * @brief Send a waypoint_ack message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param type 0: OK, 1: Error + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, type); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_ACK UNPACKING + +/** + * @brief Get field target_system from waypoint_ack message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_ack_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_ack message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_ack_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field type from waypoint_ack message + * + * @return 0: OK, 1: Error + */ +static inline uint8_t mavlink_msg_waypoint_ack_get_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a waypoint_ack message into a struct + * + * @param msg The message to decode + * @param waypoint_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_ack_decode(const mavlink_message_t* msg, mavlink_waypoint_ack_t* waypoint_ack) +{ + waypoint_ack->target_system = mavlink_msg_waypoint_ack_get_target_system(msg); + waypoint_ack->target_component = mavlink_msg_waypoint_ack_get_target_component(msg); + waypoint_ack->type = mavlink_msg_waypoint_ack_get_type(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_waypoint_clear_all.h b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_clear_all.h new file mode 100644 index 0000000000000000000000000000000000000000..5020fbada8671223344d1fd9056b41259f14f747 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_clear_all.h @@ -0,0 +1,118 @@ +// MESSAGE WAYPOINT_CLEAR_ALL PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL 45 + +typedef struct __mavlink_waypoint_clear_all_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + +} mavlink_waypoint_clear_all_t; + + + +/** + * @brief Pack a waypoint_clear_all message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL; + + 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 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a waypoint_clear_all 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 System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL; + + 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 + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a waypoint_clear_all struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_clear_all C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_clear_all_t* waypoint_clear_all) +{ + return mavlink_msg_waypoint_clear_all_pack(system_id, component_id, msg, waypoint_clear_all->target_system, waypoint_clear_all->target_component); +} + +/** + * @brief Send a waypoint_clear_all message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_clear_all_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_CLEAR_ALL UNPACKING + +/** + * @brief Get field target_system from waypoint_clear_all message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_clear_all message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a waypoint_clear_all message into a struct + * + * @param msg The message to decode + * @param waypoint_clear_all C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_clear_all_decode(const mavlink_message_t* msg, mavlink_waypoint_clear_all_t* waypoint_clear_all) +{ + waypoint_clear_all->target_system = mavlink_msg_waypoint_clear_all_get_target_system(msg); + waypoint_clear_all->target_component = mavlink_msg_waypoint_clear_all_get_target_component(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_waypoint_count.h b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_count.h new file mode 100644 index 0000000000000000000000000000000000000000..9ceacb08064ee5bfaaf678f43834e76c0c463cde --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_count.h @@ -0,0 +1,138 @@ +// MESSAGE WAYPOINT_COUNT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_COUNT 44 + +typedef struct __mavlink_waypoint_count_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint16_t count; ///< Number of Waypoints in the Sequence + +} mavlink_waypoint_count_t; + + + +/** + * @brief Pack a waypoint_count message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of Waypoints in the Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t count) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT; + + 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_uint16_t_by_index(count, i, msg->payload); // Number of Waypoints in the Sequence + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a waypoint_count 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 System ID + * @param target_component Component ID + * @param count Number of Waypoints in the Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t count) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT; + + 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_uint16_t_by_index(count, i, msg->payload); // Number of Waypoints in the Sequence + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a waypoint_count struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_count C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_count_t* waypoint_count) +{ + return mavlink_msg_waypoint_count_pack(system_id, component_id, msg, waypoint_count->target_system, waypoint_count->target_component, waypoint_count->count); +} + +/** + * @brief Send a waypoint_count message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of Waypoints in the Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_count_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, count); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_COUNT UNPACKING + +/** + * @brief Get field target_system from waypoint_count message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_count_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_count message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_count_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field count from waypoint_count message + * + * @return Number of Waypoints in the Sequence + */ +static inline uint16_t mavlink_msg_waypoint_count_get_count(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 waypoint_count message into a struct + * + * @param msg The message to decode + * @param waypoint_count C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_count_decode(const mavlink_message_t* msg, mavlink_waypoint_count_t* waypoint_count) +{ + waypoint_count->target_system = mavlink_msg_waypoint_count_get_target_system(msg); + waypoint_count->target_component = mavlink_msg_waypoint_count_get_target_component(msg); + waypoint_count->count = mavlink_msg_waypoint_count_get_count(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_waypoint_current.h b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_current.h new file mode 100644 index 0000000000000000000000000000000000000000..17f66fc298937fe031c4e02b6ad6e15cfa91f561 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_current.h @@ -0,0 +1,104 @@ +// MESSAGE WAYPOINT_CURRENT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_CURRENT 42 + +typedef struct __mavlink_waypoint_current_t +{ + uint16_t seq; ///< Sequence + +} mavlink_waypoint_current_t; + + + +/** + * @brief Pack a waypoint_current message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT; + + i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a waypoint_current 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 seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT; + + i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a waypoint_current struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_current_t* waypoint_current) +{ + return mavlink_msg_waypoint_current_pack(system_id, component_id, msg, waypoint_current->seq); +} + +/** + * @brief Send a waypoint_current message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_current_send(mavlink_channel_t chan, uint16_t seq) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_current_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seq); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_CURRENT UNPACKING + +/** + * @brief Get field seq from waypoint_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_current_get_seq(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 Decode a waypoint_current message into a struct + * + * @param msg The message to decode + * @param waypoint_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_current_decode(const mavlink_message_t* msg, mavlink_waypoint_current_t* waypoint_current) +{ + waypoint_current->seq = mavlink_msg_waypoint_current_get_seq(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_waypoint_reached.h b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_reached.h new file mode 100644 index 0000000000000000000000000000000000000000..ffcea52fc94f66b730a41f159629fee62cb14af8 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_reached.h @@ -0,0 +1,104 @@ +// MESSAGE WAYPOINT_REACHED PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_REACHED 46 + +typedef struct __mavlink_waypoint_reached_t +{ + uint16_t seq; ///< Sequence + +} mavlink_waypoint_reached_t; + + + +/** + * @brief Pack a waypoint_reached 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 seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED; + + i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a waypoint_reached 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 seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED; + + i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a waypoint_reached struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_reached C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_reached_t* waypoint_reached) +{ + return mavlink_msg_waypoint_reached_pack(system_id, component_id, msg, waypoint_reached->seq); +} + +/** + * @brief Send a waypoint_reached message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_reached_send(mavlink_channel_t chan, uint16_t seq) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_reached_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seq); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_REACHED UNPACKING + +/** + * @brief Get field seq from waypoint_reached message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_reached_get_seq(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 Decode a waypoint_reached message into a struct + * + * @param msg The message to decode + * @param waypoint_reached C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_reached_decode(const mavlink_message_t* msg, mavlink_waypoint_reached_t* waypoint_reached) +{ + waypoint_reached->seq = mavlink_msg_waypoint_reached_get_seq(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_waypoint_request.h b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_request.h new file mode 100644 index 0000000000000000000000000000000000000000..234b55c11d4da51f2c897096d2ca0e88f9c3ed2e --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_request.h @@ -0,0 +1,138 @@ +// MESSAGE WAYPOINT_REQUEST PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST 40 + +typedef struct __mavlink_waypoint_request_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint16_t seq; ///< Sequence + +} mavlink_waypoint_request_t; + + + +/** + * @brief Pack a waypoint_request message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST; + + 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_uint16_t_by_index(seq, i, msg->payload); // Sequence + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a waypoint_request 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 System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_request_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 seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST; + + 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_uint16_t_by_index(seq, i, msg->payload); // Sequence + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a waypoint_request struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_t* waypoint_request) +{ + return mavlink_msg_waypoint_request_pack(system_id, component_id, msg, waypoint_request->target_system, waypoint_request->target_component, waypoint_request->seq); +} + +/** + * @brief Send a waypoint_request message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_request_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_REQUEST UNPACKING + +/** + * @brief Get field target_system from waypoint_request message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_request_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_request message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_request_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field seq from waypoint_request message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_request_get_seq(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 waypoint_request message into a struct + * + * @param msg The message to decode + * @param waypoint_request C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_request_decode(const mavlink_message_t* msg, mavlink_waypoint_request_t* waypoint_request) +{ + waypoint_request->target_system = mavlink_msg_waypoint_request_get_target_system(msg); + waypoint_request->target_component = mavlink_msg_waypoint_request_get_target_component(msg); + waypoint_request->seq = mavlink_msg_waypoint_request_get_seq(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_waypoint_request_list.h b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_request_list.h new file mode 100644 index 0000000000000000000000000000000000000000..d4f7cf03d5d3c9bc04c86d06f2f490f668f46e12 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_request_list.h @@ -0,0 +1,118 @@ +// MESSAGE WAYPOINT_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST 43 + +typedef struct __mavlink_waypoint_request_list_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + +} mavlink_waypoint_request_list_t; + + + +/** + * @brief Pack a waypoint_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST; + + 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 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a waypoint_request_list 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 System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_request_list_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 i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST; + + 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 + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a waypoint_request_list struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_list_t* waypoint_request_list) +{ + return mavlink_msg_waypoint_request_list_pack(system_id, component_id, msg, waypoint_request_list->target_system, waypoint_request_list->target_component); +} + +/** + * @brief Send a waypoint_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_request_list_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_REQUEST_LIST UNPACKING + +/** + * @brief Get field target_system from waypoint_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_request_list_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_request_list_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a waypoint_request_list message into a struct + * + * @param msg The message to decode + * @param waypoint_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_request_list_decode(const mavlink_message_t* msg, mavlink_waypoint_request_list_t* waypoint_request_list) +{ + waypoint_request_list->target_system = mavlink_msg_waypoint_request_list_get_target_system(msg); + waypoint_request_list->target_component = mavlink_msg_waypoint_request_list_get_target_component(msg); +} diff --git a/thirdParty/mavlink/include/common/mavlink_msg_waypoint_set_current.h b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_set_current.h new file mode 100644 index 0000000000000000000000000000000000000000..6570fe4f8297e9b7e860f0f3374d90329dda1875 --- /dev/null +++ b/thirdParty/mavlink/include/common/mavlink_msg_waypoint_set_current.h @@ -0,0 +1,138 @@ +// MESSAGE WAYPOINT_SET_CURRENT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT 41 + +typedef struct __mavlink_waypoint_set_current_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint16_t seq; ///< Sequence + +} mavlink_waypoint_set_current_t; + + + +/** + * @brief Pack a waypoint_set_current message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT; + + 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_uint16_t_by_index(seq, i, msg->payload); // Sequence + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a waypoint_set_current 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 System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_set_current_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 seq) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT; + + 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_uint16_t_by_index(seq, i, msg->payload); // Sequence + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a waypoint_set_current struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_set_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_set_current_t* waypoint_set_current) +{ + return mavlink_msg_waypoint_set_current_pack(system_id, component_id, msg, waypoint_set_current->target_system, waypoint_set_current->target_component, waypoint_set_current->seq); +} + +/** + * @brief Send a waypoint_set_current message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ + mavlink_message_t msg; + mavlink_msg_waypoint_set_current_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, seq); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WAYPOINT_SET_CURRENT UNPACKING + +/** + * @brief Get field target_system from waypoint_set_current message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_set_current_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from waypoint_set_current message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_set_current_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field seq from waypoint_set_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_set_current_get_seq(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 waypoint_set_current message into a struct + * + * @param msg The message to decode + * @param waypoint_set_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_set_current_decode(const mavlink_message_t* msg, mavlink_waypoint_set_current_t* waypoint_set_current) +{ + waypoint_set_current->target_system = mavlink_msg_waypoint_set_current_get_target_system(msg); + waypoint_set_current->target_component = mavlink_msg_waypoint_set_current_get_target_component(msg); + waypoint_set_current->seq = mavlink_msg_waypoint_set_current_get_seq(msg); +} diff --git a/thirdParty/mavlink/include/documentation.dox b/thirdParty/mavlink/include/documentation.dox new file mode 100644 index 0000000000000000000000000000000000000000..49de0050e41a4cb599595a6751081bbfcb907d99 --- /dev/null +++ b/thirdParty/mavlink/include/documentation.dox @@ -0,0 +1,41 @@ +/** + * @file + * @brief MAVLink communication protocol + * + * @author Lorenz Meier + * + */ + + +/** + * @mainpage MAVLink API Documentation + * + * @section intro_sec Introduction + * + * This API documentation covers the MAVLink + * protocol developed PIXHAWK project. + * In case you have generated this documentation locally, the most recent version (generated on every commit) + * is also publicly available on the internet. + * + * @sa http://pixhawk.ethz.ch/api/qgroundcontrol/ - Groundstation code base + * @sa http://pixhawk.ethz.ch/api/mavlink - (this) MAVLink communication protocol + * @sa http://pixhawk.ethz.ch/api/imu_autopilot/ - Flight board (ARM MCU) code base + * @sa http://pixhawk.ethz.ch/api/ai_vision - Computer Vision / AI API docs + * + * @section further_sec Further Information + * + * How to run our software and a general overview of the software architecture is documented in the project + * wiki pages. + * + * @sa http://pixhawk.ethz.ch/software/mavlink/ - MAVLink main documentation + * + * See the PIXHAWK website for more information. + * + * @section usage_sec Doxygen Usage + * + * You can exclude files from being parsed into this Doxygen documentation + * by adding them to the EXCLUDE list in the file in embedded/cmake/doc/api/doxy.config.in. + * + * + * + **/ diff --git a/thirdParty/mavlink/include/mavlink_types.h b/thirdParty/mavlink/include/mavlink_types.h new file mode 100644 index 0000000000000000000000000000000000000000..2eff48ef8fec9e045131281184b5c6c6c5c8344f --- /dev/null +++ b/thirdParty/mavlink/include/mavlink_types.h @@ -0,0 +1,228 @@ +#ifndef MAVLINK_TYPES_H_ +#define MAVLINK_TYPES_H_ + +#include "inttypes.h" + +enum MAV_CLASS +{ + MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything + MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch + MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu + MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com + MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org + MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints + MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands + MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set + MAV_CLASS_NB ///< Number of autopilot classes +}; + +enum MAV_ACTION +{ + MAV_ACTION_HOLD = 0, + MAV_ACTION_MOTORS_START = 1, + MAV_ACTION_LAUNCH = 2, + MAV_ACTION_RETURN = 3, + MAV_ACTION_EMCY_LAND = 4, + MAV_ACTION_EMCY_KILL = 5, + MAV_ACTION_CONFIRM_KILL = 6, + MAV_ACTION_CONTINUE = 7, + MAV_ACTION_MOTORS_STOP = 8, + MAV_ACTION_HALT = 9, + MAV_ACTION_SHUTDOWN = 10, + MAV_ACTION_REBOOT = 11, + MAV_ACTION_SET_MANUAL = 12, + MAV_ACTION_SET_AUTO = 13, + MAV_ACTION_STORAGE_READ = 14, + MAV_ACTION_STORAGE_WRITE = 15, + MAV_ACTION_CALIBRATE_RC = 16, + MAV_ACTION_CALIBRATE_GYRO = 17, + MAV_ACTION_CALIBRATE_MAG = 18, + MAV_ACTION_CALIBRATE_ACC = 19, + MAV_ACTION_CALIBRATE_PRESSURE = 20, + MAV_ACTION_REC_START = 21, + MAV_ACTION_REC_PAUSE = 22, + MAV_ACTION_REC_STOP = 23, + MAV_ACTION_TAKEOFF = 24, + MAV_ACTION_NAVIGATE = 25, + MAV_ACTION_LAND = 26, + MAV_ACTION_LOITER = 27, + MAV_ACTION_SET_ORIGIN = 28, + MAV_ACTION_RELAY_ON = 29, + MAV_ACTION_RELAY_OFF = 30, + MAV_ACTION_GET_IMAGE = 31, + MAV_ACTION_VIDEO_START = 32, + MAV_ACTION_VIDEO_STOP = 33, + MAV_ACTION_RESET_MAP = 34, + MAV_ACTION_RESET_PLAN = 35, + MAV_ACTION_DELAY_BEFORE_COMMAND = 36, + MAV_ACTION_ASCEND_AT_RATE = 37, + 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 +}; + +enum MAV_MODE +{ + MAV_MODE_UNINIT = 0, ///< System is in undefined state + MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe + MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control + MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint + MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation + MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use + MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use + MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use + MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive + MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back +}; + +enum MAV_STATE +{ + MAV_STATE_UNINIT = 0, + MAV_STATE_BOOT, + MAV_STATE_CALIBRATING, + MAV_STATE_STANDBY, + MAV_STATE_ACTIVE, + MAV_STATE_CRITICAL, + MAV_STATE_EMERGENCY, + MAV_STATE_HILSIM, + MAV_STATE_POWEROFF +}; + +enum MAV_NAV +{ + MAV_NAV_GROUNDED = 0, + MAV_NAV_LIFTOFF, + MAV_NAV_HOLD, + MAV_NAV_WAYPOINT, + MAV_NAV_VECTOR, + MAV_NAV_RETURNING, + MAV_NAV_LANDING, + MAV_NAV_LOST, + MAV_NAV_LOITER +}; + +enum MAV_TYPE +{ + MAV_GENERIC = 0, + MAV_FIXED_WING = 1, + MAV_QUADROTOR = 2, + MAV_COAXIAL = 3, + MAV_HELICOPTER = 4, + MAV_GROUND = 5, + OCU = 6 +}; + +enum MAV_AUTOPILOT_TYPE +{ + MAV_AUTOPILOT_GENERIC = 0, + MAV_AUTOPILOT_PIXHAWK = 1, + MAV_AUTOPILOT_SLUGS = 2, + MAV_AUTOPILOT_ARDUPILOTMEGA = 3 +}; + +enum MAV_COMPONENT +{ + MAV_COMP_ID_GPS, + MAV_COMP_ID_WAYPOINTPLANNER, + MAV_COMP_ID_BLOBTRACKER, + MAV_COMP_ID_PATHPLANNER, + MAV_COMP_ID_AIRSLAM, + MAV_COMP_ID_MAPPER, + MAV_COMP_ID_CAMERA, + MAV_COMP_ID_IMU = 200, + MAV_COMP_ID_UDP_BRIDGE = 240, + MAV_COMP_ID_UART_BRIDGE = 241, + MAV_COMP_ID_SYSTEM_CONTROL = 250 +}; + +enum MAV_FRAME +{ + MAV_FRAME_GLOBAL = 0, + MAV_FRAME_LOCAL = 1, + MAV_FRAME_MISSION = 2, + MAV_FRAME_GLOBAL_RELATIVE_ALT = 3 +}; + +#define MAVLINK_STX 0x55 ///< Packet start sign +#define MAVLINK_STX_LEN 1 ///< Length of start sign +#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length + +#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) +#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + MAVLINK_STX_LEN) ///< Length of all header bytes, including core and checksum +#define MAVLINK_NUM_CHECKSUM_BYTES 2 +#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) +#define MAVLINK_NUM_NON_STX_PAYLOAD_BYTES (MAVLINK_NUM_NON_PAYLOAD_BYTES - MAVLINK_STX_LEN) + +#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length +//#define MAVLINK_MAX_DATA_LEN MAVLINK_MAX_PACKET_LEN - MAVLINK_STX_LEN + +typedef struct __mavlink_system { + uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function + uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function + uint8_t type; ///< Unused, can be used by user to store the system's type + uint8_t state; ///< Unused, can be used by user to store the system's state + uint8_t mode; ///< Unused, can be used by user to store the system's mode +} mavlink_system_t; + +typedef struct __mavlink_message { + uint8_t len; ///< Length of payload + uint8_t seq; ///< Sequence of packet + uint8_t sysid; ///< ID of message sender system/aircraft + uint8_t compid; ///< ID of the message sender component + uint8_t msgid; ///< ID of message in payload + uint8_t payload[MAVLINK_MAX_PAYLOAD_LEN]; ///< Payload data, ALIGNMENT IMPORTANT ON MCU + uint8_t ck_a; ///< Checksum high byte + uint8_t ck_b; ///< Checksum low byte +} mavlink_message_t; + +typedef enum { + MAVLINK_COMM_0, + MAVLINK_COMM_1, + MAVLINK_COMM_2, + 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, + MAVLINK_PARSE_STATE_IDLE, + MAVLINK_PARSE_STATE_GOT_STX, + MAVLINK_PARSE_STATE_GOT_SEQ, + MAVLINK_PARSE_STATE_GOT_LENGTH, + MAVLINK_PARSE_STATE_GOT_SYSID, + MAVLINK_PARSE_STATE_GOT_COMPID, + MAVLINK_PARSE_STATE_GOT_MSGID, + MAVLINK_PARSE_STATE_GOT_PAYLOAD, + MAVLINK_PARSE_STATE_GOT_CRC1 +} mavlink_parse_state_t; ///< The state machine for the comm parser + +typedef struct __mavlink_status { + uint8_t ck_a; ///< Checksum byte 1 + uint8_t ck_b; ///< Checksum byte 2 + uint8_t msg_received; ///< Number of received messages + uint8_t buffer_overrun; ///< Number of buffer overruns + uint8_t parse_error; ///< Number of parse errors + mavlink_parse_state_t parse_state; ///< Parsing state machine + uint8_t packet_idx; ///< Index in current packet + uint8_t current_rx_seq; ///< Sequence number of last packet received + uint8_t current_tx_seq; ///< Sequence number of last packet sent + uint16_t packet_rx_success_count; ///< Received packets + uint16_t packet_rx_drop_count; ///< Number of packet drops +} mavlink_status_t; + +#endif /* MAVLINK_TYPES_H_ */ diff --git a/thirdParty/mavlink/include/pixhawk/mavlink.h b/thirdParty/mavlink/include/pixhawk/mavlink.h new file mode 100644 index 0000000000000000000000000000000000000000..91159fccdd8c7e1034b50eb017a9c006a0a1cf41 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink.h @@ -0,0 +1,11 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Thursday, March 31 2011, 22:06 UTC + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#include "pixhawk.h" + +#endif diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_attitude_control.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_attitude_control.h new file mode 100644 index 0000000000000000000000000000000000000000..1a8b806f8ab2983c374e2f89f944df9772d48226 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_attitude_control.h @@ -0,0 +1,257 @@ +// MESSAGE ATTITUDE_CONTROL PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_CONTROL 85 + +typedef struct __mavlink_attitude_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_attitude_control_t; + + + +/** + * @brief Pack a attitude_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target 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_attitude_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_ATTITUDE_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); +} + +/** + * @brief Pack a attitude_control 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 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_attitude_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 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_ATTITUDE_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_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a attitude_control 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 attitude_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_control_t* attitude_control) +{ + return mavlink_msg_attitude_control_pack(system_id, component_id, msg, attitude_control->target, attitude_control->roll, attitude_control->pitch, attitude_control->yaw, attitude_control->thrust, attitude_control->roll_manual, attitude_control->pitch_manual, attitude_control->yaw_manual, attitude_control->thrust_manual); +} + +/** + * @brief Send a attitude_control message + * @param chan MAVLink channel to send the 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 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_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_attitude_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE ATTITUDE_CONTROL UNPACKING + +/** + * @brief Get field target from attitude_control message + * + * @return The system to be controlled + */ +static inline uint8_t mavlink_msg_attitude_control_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field roll from attitude_control message + * + * @return roll + */ +static inline float mavlink_msg_attitude_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 attitude_control message + * + * @return pitch + */ +static inline float mavlink_msg_attitude_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 attitude_control message + * + * @return yaw + */ +static inline float mavlink_msg_attitude_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 attitude_control message + * + * @return thrust + */ +static inline float mavlink_msg_attitude_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 attitude_control message + * + * @return roll control enabled auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_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 attitude_control message + * + * @return pitch auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_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 attitude_control message + * + * @return yaw auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_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 attitude_control message + * + * @return thrust auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_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]; +} + +/** + * @brief Decode a attitude_control message into a struct + * + * @param msg The message to decode + * @param attitude_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_control_decode(const mavlink_message_t* msg, mavlink_attitude_control_t* attitude_control) +{ + attitude_control->target = mavlink_msg_attitude_control_get_target(msg); + attitude_control->roll = mavlink_msg_attitude_control_get_roll(msg); + attitude_control->pitch = mavlink_msg_attitude_control_get_pitch(msg); + attitude_control->yaw = mavlink_msg_attitude_control_get_yaw(msg); + attitude_control->thrust = mavlink_msg_attitude_control_get_thrust(msg); + attitude_control->roll_manual = mavlink_msg_attitude_control_get_roll_manual(msg); + attitude_control->pitch_manual = mavlink_msg_attitude_control_get_pitch_manual(msg); + attitude_control->yaw_manual = mavlink_msg_attitude_control_get_yaw_manual(msg); + attitude_control->thrust_manual = mavlink_msg_attitude_control_get_thrust_manual(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_aux_status.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_aux_status.h new file mode 100644 index 0000000000000000000000000000000000000000..f9dbde8c86ca4350705a5d8dfe9cec05c7240571 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_aux_status.h @@ -0,0 +1,204 @@ +// MESSAGE AUX_STATUS PACKING + +#define MAVLINK_MSG_ID_AUX_STATUS 142 + +typedef struct __mavlink_aux_status_t +{ + uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + uint16_t i2c0_err_count; ///< Number of I2C errors since startup + uint16_t i2c1_err_count; ///< Number of I2C errors since startup + uint16_t spi0_err_count; ///< Number of I2C errors since startup + uint16_t spi1_err_count; ///< Number of I2C errors since startup + uint16_t uart_total_err_count; ///< Number of I2C errors since startup + +} mavlink_aux_status_t; + + + +/** + * @brief Pack a aux_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param i2c0_err_count Number of I2C errors since startup + * @param i2c1_err_count Number of I2C errors since startup + * @param spi0_err_count Number of I2C errors since startup + * @param spi1_err_count Number of I2C errors since startup + * @param uart_total_err_count Number of I2C errors since startup + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_aux_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_AUX_STATUS; + + i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); // Number of I2C errors since startup + i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); // Number of I2C errors since startup + i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); // Number of I2C errors since startup + i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); // Number of I2C errors since startup + i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); // Number of I2C errors since startup + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a aux_status 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 load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param i2c0_err_count Number of I2C errors since startup + * @param i2c1_err_count Number of I2C errors since startup + * @param spi0_err_count Number of I2C errors since startup + * @param spi1_err_count Number of I2C errors since startup + * @param uart_total_err_count Number of I2C errors since startup + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_aux_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_AUX_STATUS; + + i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); // Number of I2C errors since startup + i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); // Number of I2C errors since startup + i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); // Number of I2C errors since startup + i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); // Number of I2C errors since startup + i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); // Number of I2C errors since startup + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a aux_status 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 aux_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_aux_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aux_status_t* aux_status) +{ + return mavlink_msg_aux_status_pack(system_id, component_id, msg, aux_status->load, aux_status->i2c0_err_count, aux_status->i2c1_err_count, aux_status->spi0_err_count, aux_status->spi1_err_count, aux_status->uart_total_err_count); +} + +/** + * @brief Send a aux_status message + * @param chan MAVLink channel to send the message + * + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param i2c0_err_count Number of I2C errors since startup + * @param i2c1_err_count Number of I2C errors since startup + * @param spi0_err_count Number of I2C errors since startup + * @param spi1_err_count Number of I2C errors since startup + * @param uart_total_err_count Number of I2C errors since startup + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_aux_status_send(mavlink_channel_t chan, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count) +{ + mavlink_message_t msg; + mavlink_msg_aux_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, load, i2c0_err_count, i2c1_err_count, spi0_err_count, spi1_err_count, uart_total_err_count); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE AUX_STATUS UNPACKING + +/** + * @brief Get field load from aux_status message + * + * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + */ +static inline uint16_t mavlink_msg_aux_status_get_load(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 i2c0_err_count from aux_status message + * + * @return Number of I2C errors since startup + */ +static inline uint16_t mavlink_msg_aux_status_get_i2c0_err_count(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 i2c1_err_count from aux_status message + * + * @return Number of I2C errors since startup + */ +static inline uint16_t mavlink_msg_aux_status_get_i2c1_err_count(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 spi0_err_count from aux_status message + * + * @return Number of I2C errors since startup + */ +static inline uint16_t mavlink_msg_aux_status_get_spi0_err_count(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 spi1_err_count from aux_status message + * + * @return Number of I2C errors since startup + */ +static inline uint16_t mavlink_msg_aux_status_get_spi1_err_count(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; +} + +/** + * @brief Get field uart_total_err_count from aux_status message + * + * @return Number of I2C errors since startup + */ +static inline uint16_t mavlink_msg_aux_status_get_uart_total_err_count(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)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Decode a aux_status message into a struct + * + * @param msg The message to decode + * @param aux_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_aux_status_decode(const mavlink_message_t* msg, mavlink_aux_status_t* aux_status) +{ + aux_status->load = mavlink_msg_aux_status_get_load(msg); + aux_status->i2c0_err_count = mavlink_msg_aux_status_get_i2c0_err_count(msg); + aux_status->i2c1_err_count = mavlink_msg_aux_status_get_i2c1_err_count(msg); + aux_status->spi0_err_count = mavlink_msg_aux_status_get_spi0_err_count(msg); + aux_status->spi1_err_count = mavlink_msg_aux_status_get_spi1_err_count(msg); + aux_status->uart_total_err_count = mavlink_msg_aux_status_get_uart_total_err_count(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_brief_feature.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_brief_feature.h new file mode 100644 index 0000000000000000000000000000000000000000..a61e13bcde2c02a4b79449affb839956a6baf5bf --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_brief_feature.h @@ -0,0 +1,249 @@ +// MESSAGE BRIEF_FEATURE PACKING + +#define MAVLINK_MSG_ID_BRIEF_FEATURE 172 + +typedef struct __mavlink_brief_feature_t +{ + float x; ///< x position in m + float y; ///< y position in m + float z; ///< z position in m + uint8_t orientation_assignment; ///< Orientation assignment 0: false, 1:true + uint16_t size; ///< Size in pixels + uint16_t orientation; ///< Orientation + uint8_t descriptor[32]; ///< Descriptor + float response; ///< Harris operator response at this location + +} mavlink_brief_feature_t; + +#define MAVLINK_MSG_BRIEF_FEATURE_FIELD_DESCRIPTOR_LEN 32 + + +/** + * @brief Pack a brief_feature 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 x x position in m + * @param y y position in m + * @param z z position in m + * @param orientation_assignment Orientation assignment 0: false, 1:true + * @param size Size in pixels + * @param orientation Orientation + * @param descriptor Descriptor + * @param response Harris operator response at this location + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t* descriptor, float response) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE; + + i += put_float_by_index(x, i, msg->payload); // x position in m + i += put_float_by_index(y, i, msg->payload); // y position in m + i += put_float_by_index(z, i, msg->payload); // z position in m + i += put_uint8_t_by_index(orientation_assignment, i, msg->payload); // Orientation assignment 0: false, 1:true + i += put_uint16_t_by_index(size, i, msg->payload); // Size in pixels + i += put_uint16_t_by_index(orientation, i, msg->payload); // Orientation + i += put_array_by_index((const int8_t*)descriptor, sizeof(uint8_t)*32, i, msg->payload); // Descriptor + i += put_float_by_index(response, i, msg->payload); // Harris operator response at this location + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a brief_feature 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 x x position in m + * @param y y position in m + * @param z z position in m + * @param orientation_assignment Orientation assignment 0: false, 1:true + * @param size Size in pixels + * @param orientation Orientation + * @param descriptor Descriptor + * @param response Harris operator response at this location + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t* descriptor, float response) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE; + + i += put_float_by_index(x, i, msg->payload); // x position in m + i += put_float_by_index(y, i, msg->payload); // y position in m + i += put_float_by_index(z, i, msg->payload); // z position in m + i += put_uint8_t_by_index(orientation_assignment, i, msg->payload); // Orientation assignment 0: false, 1:true + i += put_uint16_t_by_index(size, i, msg->payload); // Size in pixels + i += put_uint16_t_by_index(orientation, i, msg->payload); // Orientation + i += put_array_by_index((const int8_t*)descriptor, sizeof(uint8_t)*32, i, msg->payload); // Descriptor + i += put_float_by_index(response, i, msg->payload); // Harris operator response at this location + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a brief_feature 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 brief_feature C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_brief_feature_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_brief_feature_t* brief_feature) +{ + return mavlink_msg_brief_feature_pack(system_id, component_id, msg, brief_feature->x, brief_feature->y, brief_feature->z, brief_feature->orientation_assignment, brief_feature->size, brief_feature->orientation, brief_feature->descriptor, brief_feature->response); +} + +/** + * @brief Send a brief_feature message + * @param chan MAVLink channel to send the message + * + * @param x x position in m + * @param y y position in m + * @param z z position in m + * @param orientation_assignment Orientation assignment 0: false, 1:true + * @param size Size in pixels + * @param orientation Orientation + * @param descriptor Descriptor + * @param response Harris operator response at this location + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_brief_feature_send(mavlink_channel_t chan, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t* descriptor, float response) +{ + mavlink_message_t msg; + mavlink_msg_brief_feature_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, x, y, z, orientation_assignment, size, orientation, descriptor, response); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE BRIEF_FEATURE UNPACKING + +/** + * @brief Get field x from brief_feature message + * + * @return x position in m + */ +static inline float mavlink_msg_brief_feature_get_x(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 y from brief_feature message + * + * @return y position in m + */ +static inline float mavlink_msg_brief_feature_get_y(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 z from brief_feature message + * + * @return z position in m + */ +static inline float mavlink_msg_brief_feature_get_z(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 orientation_assignment from brief_feature message + * + * @return Orientation assignment 0: false, 1:true + */ +static inline uint8_t mavlink_msg_brief_feature_get_orientation_assignment(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0]; +} + +/** + * @brief Get field size from brief_feature message + * + * @return Size in pixels + */ +static inline uint16_t mavlink_msg_brief_feature_get_size(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field orientation from brief_feature message + * + * @return Orientation + */ +static inline uint16_t mavlink_msg_brief_feature_get_orientation(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field descriptor from brief_feature message + * + * @return Descriptor + */ +static inline uint16_t mavlink_msg_brief_feature_get_descriptor(const mavlink_message_t* msg, uint8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t), sizeof(uint8_t)*32); + return sizeof(uint8_t)*32; +} + +/** + * @brief Get field response from brief_feature message + * + * @return Harris operator response at this location + */ +static inline float mavlink_msg_brief_feature_get_response(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[0]; + r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[1]; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[2]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)*32)[3]; + return (float)r.f; +} + +/** + * @brief Decode a brief_feature message into a struct + * + * @param msg The message to decode + * @param brief_feature C-struct to decode the message contents into + */ +static inline void mavlink_msg_brief_feature_decode(const mavlink_message_t* msg, mavlink_brief_feature_t* brief_feature) +{ + brief_feature->x = mavlink_msg_brief_feature_get_x(msg); + brief_feature->y = mavlink_msg_brief_feature_get_y(msg); + brief_feature->z = mavlink_msg_brief_feature_get_z(msg); + brief_feature->orientation_assignment = mavlink_msg_brief_feature_get_orientation_assignment(msg); + brief_feature->size = mavlink_msg_brief_feature_get_size(msg); + brief_feature->orientation = mavlink_msg_brief_feature_get_orientation(msg); + mavlink_msg_brief_feature_get_descriptor(msg, brief_feature->descriptor); + brief_feature->response = mavlink_msg_brief_feature_get_response(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_data_transmission_handshake.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_data_transmission_handshake.h new file mode 100644 index 0000000000000000000000000000000000000000..e9e69f7c9f53319f4c5c4973ebb80e65f3e72750 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_data_transmission_handshake.h @@ -0,0 +1,174 @@ +// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING + +#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 170 + +typedef struct __mavlink_data_transmission_handshake_t +{ + uint8_t type; ///< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + uint32_t size; ///< total data size in bytes (set on ACK only) + uint8_t packets; ///< number of packets beeing sent (set on ACK only) + uint8_t payload; ///< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + uint8_t jpg_quality; ///< JPEG quality out of [1,100] + +} mavlink_data_transmission_handshake_t; + + + +/** + * @brief Pack a data_transmission_handshake message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; + + i += put_uint8_t_by_index(type, i, msg->payload); // type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + i += put_uint32_t_by_index(size, i, msg->payload); // total data size in bytes (set on ACK only) + i += put_uint8_t_by_index(packets, i, msg->payload); // number of packets beeing sent (set on ACK only) + i += put_uint8_t_by_index(payload, i, msg->payload); // payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + i += put_uint8_t_by_index(jpg_quality, i, msg->payload); // JPEG quality out of [1,100] + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a data_transmission_handshake message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; + + i += put_uint8_t_by_index(type, i, msg->payload); // type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + i += put_uint32_t_by_index(size, i, msg->payload); // total data size in bytes (set on ACK only) + i += put_uint8_t_by_index(packets, i, msg->payload); // number of packets beeing sent (set on ACK only) + i += put_uint8_t_by_index(payload, i, msg->payload); // payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + i += put_uint8_t_by_index(jpg_quality, i, msg->payload); // JPEG quality out of [1,100] + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a data_transmission_handshake 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_transmission_handshake C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) +{ + return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); +} + +/** + * @brief Send a data_transmission_handshake message + * @param chan MAVLink channel to send the message + * + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality) +{ + mavlink_message_t msg; + mavlink_msg_data_transmission_handshake_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, size, packets, payload, jpg_quality); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING + +/** + * @brief Get field type from data_transmission_handshake message + * + * @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field size from data_transmission_handshake message + * + * @return total data size in bytes (set on ACK only) + */ +static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg) +{ + 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; +} + +/** + * @brief Get field packets from data_transmission_handshake message + * + * @return number of packets beeing sent (set on ACK only) + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t))[0]; +} + +/** + * @brief Get field payload from data_transmission_handshake message + * + * @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field jpg_quality from data_transmission_handshake message + * + * @return JPEG quality out of [1,100] + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Decode a data_transmission_handshake message into a struct + * + * @param msg The message to decode + * @param data_transmission_handshake C-struct to decode the message contents into + */ +static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake) +{ + data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg); + data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg); + data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg); + data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg); + data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_encapsulated_data.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_encapsulated_data.h new file mode 100644 index 0000000000000000000000000000000000000000..c2c040ae65bcd63a12f434bcfba69f74636c4b43 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_encapsulated_data.h @@ -0,0 +1,124 @@ +// MESSAGE ENCAPSULATED_DATA PACKING + +#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 171 + +typedef struct __mavlink_encapsulated_data_t +{ + uint16_t seqnr; ///< sequence number (starting with 0 on every transmission) + uint8_t data[253]; ///< image data bytes + +} mavlink_encapsulated_data_t; + +#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253 + + +/** + * @brief Pack a encapsulated_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seqnr, const uint8_t* data) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; + + i += put_uint16_t_by_index(seqnr, i, msg->payload); // sequence number (starting with 0 on every transmission) + i += put_array_by_index((const int8_t*)data, sizeof(uint8_t)*253, i, msg->payload); // image data bytes + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a encapsulated_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seqnr, const uint8_t* data) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; + + i += put_uint16_t_by_index(seqnr, i, msg->payload); // sequence number (starting with 0 on every transmission) + i += put_array_by_index((const int8_t*)data, sizeof(uint8_t)*253, i, msg->payload); // image data bytes + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a encapsulated_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 encapsulated_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) +{ + return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data); +} + +/** + * @brief Send a encapsulated_data message + * @param chan MAVLink channel to send the message + * + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t* data) +{ + mavlink_message_t msg; + mavlink_msg_encapsulated_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seqnr, data); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE ENCAPSULATED_DATA UNPACKING + +/** + * @brief Get field seqnr from encapsulated_data message + * + * @return sequence number (starting with 0 on every transmission) + */ +static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload)[0]; + r.b[0] = (msg->payload)[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field data from encapsulated_data message + * + * @return image data bytes + */ +static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint16_t), sizeof(uint8_t)*253); + return sizeof(uint8_t)*253; +} + +/** + * @brief Decode a encapsulated_data message into a struct + * + * @param msg The message to decode + * @param encapsulated_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data) +{ + encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg); + mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_image_available.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_image_available.h new file mode 100644 index 0000000000000000000000000000000000000000..472449988b475b37aa28f60dc83bb0363d9c584b --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_image_available.h @@ -0,0 +1,520 @@ +// MESSAGE IMAGE_AVAILABLE PACKING + +#define MAVLINK_MSG_ID_IMAGE_AVAILABLE 103 + +typedef struct __mavlink_image_available_t +{ + uint64_t cam_id; ///< Camera id + uint8_t cam_no; ///< Camera # (starts with 0) + uint64_t timestamp; ///< Timestamp + uint64_t valid_until; ///< Until which timestamp this buffer will stay valid + uint32_t img_seq; ///< The image sequence number + uint32_t img_buf_index; ///< Position of the image in the buffer, starts with 0 + uint16_t width; ///< Image width + uint16_t height; ///< Image height + uint16_t depth; ///< Image depth + uint8_t channels; ///< Image channels + uint32_t key; ///< Shared memory area key + uint32_t exposure; ///< Exposure time, in microseconds + float gain; ///< Camera gain + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad + float local_z; ///< Local frame Z coordinate (height over ground) + float lat; ///< GPS X coordinate + float lon; ///< GPS Y coordinate + float alt; ///< Global frame altitude + +} mavlink_image_available_t; + + + +/** + * @brief Pack a image_available 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 cam_id Camera id + * @param cam_no Camera # (starts with 0) + * @param timestamp Timestamp + * @param valid_until Until which timestamp this buffer will stay valid + * @param img_seq The image sequence number + * @param img_buf_index Position of the image in the buffer, starts with 0 + * @param width Image width + * @param height Image height + * @param depth Image depth + * @param channels Image channels + * @param key Shared memory area key + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; + + i += put_uint64_t_by_index(cam_id, i, msg->payload); // Camera id + i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera # (starts with 0) + i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp + i += put_uint64_t_by_index(valid_until, i, msg->payload); // Until which timestamp this buffer will stay valid + i += put_uint32_t_by_index(img_seq, i, msg->payload); // The image sequence number + i += put_uint32_t_by_index(img_buf_index, i, msg->payload); // Position of the image in the buffer, starts with 0 + i += put_uint16_t_by_index(width, i, msg->payload); // Image width + i += put_uint16_t_by_index(height, i, msg->payload); // Image height + i += put_uint16_t_by_index(depth, i, msg->payload); // Image depth + i += put_uint8_t_by_index(channels, i, msg->payload); // Image channels + i += put_uint32_t_by_index(key, i, msg->payload); // Shared memory area key + i += put_uint32_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds + i += put_float_by_index(gain, i, msg->payload); // Camera gain + i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad + i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground) + i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate + i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate + i += put_float_by_index(alt, i, msg->payload); // Global frame altitude + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a image_available 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 cam_id Camera id + * @param cam_no Camera # (starts with 0) + * @param timestamp Timestamp + * @param valid_until Until which timestamp this buffer will stay valid + * @param img_seq The image sequence number + * @param img_buf_index Position of the image in the buffer, starts with 0 + * @param width Image width + * @param height Image height + * @param depth Image depth + * @param channels Image channels + * @param key Shared memory area key + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; + + i += put_uint64_t_by_index(cam_id, i, msg->payload); // Camera id + i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera # (starts with 0) + i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp + i += put_uint64_t_by_index(valid_until, i, msg->payload); // Until which timestamp this buffer will stay valid + i += put_uint32_t_by_index(img_seq, i, msg->payload); // The image sequence number + i += put_uint32_t_by_index(img_buf_index, i, msg->payload); // Position of the image in the buffer, starts with 0 + i += put_uint16_t_by_index(width, i, msg->payload); // Image width + i += put_uint16_t_by_index(height, i, msg->payload); // Image height + i += put_uint16_t_by_index(depth, i, msg->payload); // Image depth + i += put_uint8_t_by_index(channels, i, msg->payload); // Image channels + i += put_uint32_t_by_index(key, i, msg->payload); // Shared memory area key + i += put_uint32_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds + i += put_float_by_index(gain, i, msg->payload); // Camera gain + i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad + i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground) + i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate + i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate + i += put_float_by_index(alt, i, msg->payload); // Global frame altitude + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a image_available 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 image_available C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_available_t* image_available) +{ + return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt); +} + +/** + * @brief Send a image_available message + * @param chan MAVLink channel to send the message + * + * @param cam_id Camera id + * @param cam_no Camera # (starts with 0) + * @param timestamp Timestamp + * @param valid_until Until which timestamp this buffer will stay valid + * @param img_seq The image sequence number + * @param img_buf_index Position of the image in the buffer, starts with 0 + * @param width Image width + * @param height Image height + * @param depth Image depth + * @param channels Image channels + * @param key Shared memory area key + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +{ + mavlink_message_t msg; + mavlink_msg_image_available_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_id, cam_no, timestamp, valid_until, img_seq, img_buf_index, width, height, depth, channels, key, exposure, gain, roll, pitch, yaw, local_z, lat, lon, alt); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE IMAGE_AVAILABLE UNPACKING + +/** + * @brief Get field cam_id from image_available message + * + * @return Camera id + */ +static inline uint64_t mavlink_msg_image_available_get_cam_id(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field cam_no from image_available message + * + * @return Camera # (starts with 0) + */ +static inline uint8_t mavlink_msg_image_available_get_cam_no(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint64_t))[0]; +} + +/** + * @brief Get field timestamp from image_available message + * + * @return Timestamp + */ +static inline uint64_t mavlink_msg_image_available_get_timestamp(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0]; + r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1]; + r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2]; + r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3]; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[4]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[5]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[6]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field valid_until from image_available message + * + * @return Until which timestamp this buffer will stay valid + */ +static inline uint64_t mavlink_msg_image_available_get_valid_until(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[0]; + r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[1]; + r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[2]; + r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[3]; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[4]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[5]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[6]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field img_seq from image_available message + * + * @return The image sequence number + */ +static inline uint32_t mavlink_msg_image_available_get_img_seq(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[3]; + return (uint32_t)r.i; +} + +/** + * @brief Get field img_buf_index from image_available message + * + * @return Position of the image in the buffer, starts with 0 + */ +static inline uint32_t mavlink_msg_image_available_get_img_buf_index(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[3]; + return (uint32_t)r.i; +} + +/** + * @brief Get field width from image_available message + * + * @return Image width + */ +static inline uint16_t mavlink_msg_image_available_get_width(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field height from image_available message + * + * @return Image height + */ +static inline uint16_t mavlink_msg_image_available_get_height(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field depth from image_available message + * + * @return Image depth + */ +static inline uint16_t mavlink_msg_image_available_get_depth(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field channels from image_available message + * + * @return Image channels + */ +static inline uint8_t mavlink_msg_image_available_get_channels(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; +} + +/** + * @brief Get field key from image_available message + * + * @return Shared memory area key + */ +static inline uint32_t mavlink_msg_image_available_get_key(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[3]; + return (uint32_t)r.i; +} + +/** + * @brief Get field exposure from image_available message + * + * @return Exposure time, in microseconds + */ +static inline uint32_t mavlink_msg_image_available_get_exposure(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[3]; + return (uint32_t)r.i; +} + +/** + * @brief Get field gain from image_available message + * + * @return Camera gain + */ +static inline float mavlink_msg_image_available_get_gain(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field roll from image_available message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_image_available_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from image_available message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_image_available_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from image_available message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_image_available_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field local_z from image_available message + * + * @return Local frame Z coordinate (height over ground) + */ +static inline float mavlink_msg_image_available_get_local_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field lat from image_available message + * + * @return GPS X coordinate + */ +static inline float mavlink_msg_image_available_get_lat(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field lon from image_available message + * + * @return GPS Y coordinate + */ +static inline float mavlink_msg_image_available_get_lon(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field alt from image_available message + * + * @return Global frame altitude + */ +static inline float mavlink_msg_image_available_get_alt(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a image_available message into a struct + * + * @param msg The message to decode + * @param image_available C-struct to decode the message contents into + */ +static inline void mavlink_msg_image_available_decode(const mavlink_message_t* msg, mavlink_image_available_t* image_available) +{ + image_available->cam_id = mavlink_msg_image_available_get_cam_id(msg); + image_available->cam_no = mavlink_msg_image_available_get_cam_no(msg); + image_available->timestamp = mavlink_msg_image_available_get_timestamp(msg); + image_available->valid_until = mavlink_msg_image_available_get_valid_until(msg); + image_available->img_seq = mavlink_msg_image_available_get_img_seq(msg); + image_available->img_buf_index = mavlink_msg_image_available_get_img_buf_index(msg); + image_available->width = mavlink_msg_image_available_get_width(msg); + image_available->height = mavlink_msg_image_available_get_height(msg); + image_available->depth = mavlink_msg_image_available_get_depth(msg); + image_available->channels = mavlink_msg_image_available_get_channels(msg); + image_available->key = mavlink_msg_image_available_get_key(msg); + image_available->exposure = mavlink_msg_image_available_get_exposure(msg); + image_available->gain = mavlink_msg_image_available_get_gain(msg); + image_available->roll = mavlink_msg_image_available_get_roll(msg); + image_available->pitch = mavlink_msg_image_available_get_pitch(msg); + image_available->yaw = mavlink_msg_image_available_get_yaw(msg); + image_available->local_z = mavlink_msg_image_available_get_local_z(msg); + image_available->lat = mavlink_msg_image_available_get_lat(msg); + image_available->lon = mavlink_msg_image_available_get_lon(msg); + image_available->alt = mavlink_msg_image_available_get_alt(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_image_trigger_control.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_image_trigger_control.h new file mode 100644 index 0000000000000000000000000000000000000000..90aa9dcf4e8659e59fe0be38ece0c3cbecd9ade1 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_image_trigger_control.h @@ -0,0 +1,101 @@ +// MESSAGE IMAGE_TRIGGER_CONTROL PACKING + +#define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL 102 + +typedef struct __mavlink_image_trigger_control_t +{ + uint8_t enable; ///< 0 to disable, 1 to enable + +} mavlink_image_trigger_control_t; + + + +/** + * @brief Pack a image_trigger_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param enable 0 to disable, 1 to enable + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_trigger_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t enable) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL; + + i += put_uint8_t_by_index(enable, i, msg->payload); // 0 to disable, 1 to enable + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a image_trigger_control 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 enable 0 to disable, 1 to enable + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_trigger_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enable) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL; + + i += put_uint8_t_by_index(enable, i, msg->payload); // 0 to disable, 1 to enable + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a image_trigger_control 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 image_trigger_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_image_trigger_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_trigger_control_t* image_trigger_control) +{ + return mavlink_msg_image_trigger_control_pack(system_id, component_id, msg, image_trigger_control->enable); +} + +/** + * @brief Send a image_trigger_control message + * @param chan MAVLink channel to send the message + * + * @param enable 0 to disable, 1 to enable + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_image_trigger_control_send(mavlink_channel_t chan, uint8_t enable) +{ + mavlink_message_t msg; + mavlink_msg_image_trigger_control_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, enable); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE IMAGE_TRIGGER_CONTROL UNPACKING + +/** + * @brief Get field enable from image_trigger_control message + * + * @return 0 to disable, 1 to enable + */ +static inline uint8_t mavlink_msg_image_trigger_control_get_enable(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Decode a image_trigger_control message into a struct + * + * @param msg The message to decode + * @param image_trigger_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_image_trigger_control_decode(const mavlink_message_t* msg, mavlink_image_trigger_control_t* image_trigger_control) +{ + image_trigger_control->enable = mavlink_msg_image_trigger_control_get_enable(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_image_triggered.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_image_triggered.h new file mode 100644 index 0000000000000000000000000000000000000000..01f8a9203e2e7290bff9bfb034c4c10fcdb954cd --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_image_triggered.h @@ -0,0 +1,286 @@ +// MESSAGE IMAGE_TRIGGERED PACKING + +#define MAVLINK_MSG_ID_IMAGE_TRIGGERED 101 + +typedef struct __mavlink_image_triggered_t +{ + uint64_t timestamp; ///< Timestamp + uint32_t seq; ///< IMU seq + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad + float local_z; ///< Local frame Z coordinate (height over ground) + float lat; ///< GPS X coordinate + float lon; ///< GPS Y coordinate + float alt; ///< Global frame altitude + +} mavlink_image_triggered_t; + + + +/** + * @brief Pack a image_triggered 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 timestamp Timestamp + * @param seq IMU seq + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; + + i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp + i += put_uint32_t_by_index(seq, i, msg->payload); // IMU seq + i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad + i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground) + i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate + i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate + i += put_float_by_index(alt, i, msg->payload); // Global frame altitude + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a image_triggered 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 timestamp Timestamp + * @param seq IMU seq + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; + + i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp + i += put_uint32_t_by_index(seq, i, msg->payload); // IMU seq + i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad + i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground) + i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate + i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate + i += put_float_by_index(alt, i, msg->payload); // Global frame altitude + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a image_triggered 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 image_triggered C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered) +{ + return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt); +} + +/** + * @brief Send a image_triggered message + * @param chan MAVLink channel to send the message + * + * @param timestamp Timestamp + * @param seq IMU seq + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt) +{ + mavlink_message_t msg; + mavlink_msg_image_triggered_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, timestamp, seq, roll, pitch, yaw, local_z, lat, lon, alt); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE IMAGE_TRIGGERED UNPACKING + +/** + * @brief Get field timestamp from image_triggered message + * + * @return Timestamp + */ +static inline uint64_t mavlink_msg_image_triggered_get_timestamp(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field seq from image_triggered message + * + * @return IMU seq + */ +static inline uint32_t mavlink_msg_image_triggered_get_seq(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 (uint32_t)r.i; +} + +/** + * @brief Get field roll from image_triggered message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_image_triggered_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from image_triggered message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_image_triggered_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from image_triggered message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_image_triggered_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field local_z from image_triggered message + * + * @return Local frame Z coordinate (height over ground) + */ +static inline float mavlink_msg_image_triggered_get_local_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field lat from image_triggered message + * + * @return GPS X coordinate + */ +static inline float mavlink_msg_image_triggered_get_lat(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field lon from image_triggered message + * + * @return GPS Y coordinate + */ +static inline float mavlink_msg_image_triggered_get_lon(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field alt from image_triggered message + * + * @return Global frame altitude + */ +static inline float mavlink_msg_image_triggered_get_alt(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a image_triggered message into a struct + * + * @param msg The message to decode + * @param image_triggered C-struct to decode the message contents into + */ +static inline void mavlink_msg_image_triggered_decode(const mavlink_message_t* msg, mavlink_image_triggered_t* image_triggered) +{ + image_triggered->timestamp = mavlink_msg_image_triggered_get_timestamp(msg); + image_triggered->seq = mavlink_msg_image_triggered_get_seq(msg); + image_triggered->roll = mavlink_msg_image_triggered_get_roll(msg); + image_triggered->pitch = mavlink_msg_image_triggered_get_pitch(msg); + image_triggered->yaw = mavlink_msg_image_triggered_get_yaw(msg); + image_triggered->local_z = mavlink_msg_image_triggered_get_local_z(msg); + image_triggered->lat = mavlink_msg_image_triggered_get_lat(msg); + image_triggered->lon = mavlink_msg_image_triggered_get_lon(msg); + image_triggered->alt = mavlink_msg_image_triggered_get_alt(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_marker.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_marker.h new file mode 100644 index 0000000000000000000000000000000000000000..fb275534ae15fd00cd590beec1002677fc68f050 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_marker.h @@ -0,0 +1,236 @@ +// MESSAGE MARKER PACKING + +#define MAVLINK_MSG_ID_MARKER 130 + +typedef struct __mavlink_marker_t +{ + uint16_t id; ///< ID + float x; ///< x position + float y; ///< y position + float z; ///< z position + float roll; ///< roll orientation + float pitch; ///< pitch orientation + float yaw; ///< yaw orientation + +} mavlink_marker_t; + + + +/** + * @brief Pack a marker message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param id ID + * @param x x position + * @param y y position + * @param z z position + * @param roll roll orientation + * @param pitch pitch orientation + * @param yaw yaw orientation + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_MARKER; + + i += put_uint16_t_by_index(id, i, msg->payload); // ID + i += put_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(roll, i, msg->payload); // roll orientation + i += put_float_by_index(pitch, i, msg->payload); // pitch orientation + i += put_float_by_index(yaw, i, msg->payload); // yaw orientation + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a marker 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 id ID + * @param x x position + * @param y y position + * @param z z position + * @param roll roll orientation + * @param pitch pitch orientation + * @param yaw yaw orientation + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_MARKER; + + i += put_uint16_t_by_index(id, i, msg->payload); // ID + i += put_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(roll, i, msg->payload); // roll orientation + i += put_float_by_index(pitch, i, msg->payload); // pitch orientation + i += put_float_by_index(yaw, i, msg->payload); // yaw orientation + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a marker 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 marker C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_marker_t* marker) +{ + return mavlink_msg_marker_pack(system_id, component_id, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw); +} + +/** + * @brief Send a marker message + * @param chan MAVLink channel to send the message + * + * @param id ID + * @param x x position + * @param y y position + * @param z z position + * @param roll roll orientation + * @param pitch pitch orientation + * @param yaw yaw orientation + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_marker_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, id, x, y, z, roll, pitch, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE MARKER UNPACKING + +/** + * @brief Get field id from marker message + * + * @return ID + */ +static inline uint16_t mavlink_msg_marker_get_id(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 x from marker message + * + * @return x position + */ +static inline float mavlink_msg_marker_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from marker message + * + * @return y position + */ +static inline float mavlink_msg_marker_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from marker message + * + * @return z position + */ +static inline float mavlink_msg_marker_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field roll from marker message + * + * @return roll orientation + */ +static inline float mavlink_msg_marker_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from marker message + * + * @return pitch orientation + */ +static inline float mavlink_msg_marker_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from marker message + * + * @return yaw orientation + */ +static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a marker message into a struct + * + * @param msg The message to decode + * @param marker C-struct to decode the message contents into + */ +static inline void mavlink_msg_marker_decode(const mavlink_message_t* msg, mavlink_marker_t* marker) +{ + marker->id = mavlink_msg_marker_get_id(msg); + marker->x = mavlink_msg_marker_get_x(msg); + marker->y = mavlink_msg_marker_get_y(msg); + marker->z = mavlink_msg_marker_get_z(msg); + marker->roll = mavlink_msg_marker_get_roll(msg); + marker->pitch = mavlink_msg_marker_get_pitch(msg); + marker->yaw = mavlink_msg_marker_get_yaw(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_pattern_detected.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_pattern_detected.h new file mode 100644 index 0000000000000000000000000000000000000000..1a2b46596b72bc27a50d9dae2812abf412663230 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_pattern_detected.h @@ -0,0 +1,160 @@ +// MESSAGE PATTERN_DETECTED PACKING + +#define MAVLINK_MSG_ID_PATTERN_DETECTED 160 + +typedef struct __mavlink_pattern_detected_t +{ + uint8_t type; ///< 0: Pattern, 1: Letter + float confidence; ///< Confidence of detection + int8_t file[100]; ///< Pattern file name + uint8_t detected; ///< Accepted as true detection, 0 no, 1 yes + +} mavlink_pattern_detected_t; + +#define MAVLINK_MSG_PATTERN_DETECTED_FIELD_FILE_LEN 100 + + +/** + * @brief Pack a pattern_detected message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type 0: Pattern, 1: Letter + * @param confidence Confidence of detection + * @param file Pattern file name + * @param detected Accepted as true detection, 0 no, 1 yes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, float confidence, const int8_t* file, uint8_t detected) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED; + + i += put_uint8_t_by_index(type, i, msg->payload); // 0: Pattern, 1: Letter + i += put_float_by_index(confidence, i, msg->payload); // Confidence of detection + i += put_array_by_index(file, 100, i, msg->payload); // Pattern file name + i += put_uint8_t_by_index(detected, i, msg->payload); // Accepted as true detection, 0 no, 1 yes + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a pattern_detected 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 type 0: Pattern, 1: Letter + * @param confidence Confidence of detection + * @param file Pattern file name + * @param detected Accepted as true detection, 0 no, 1 yes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_pattern_detected_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, float confidence, const int8_t* file, uint8_t detected) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED; + + i += put_uint8_t_by_index(type, i, msg->payload); // 0: Pattern, 1: Letter + i += put_float_by_index(confidence, i, msg->payload); // Confidence of detection + i += put_array_by_index(file, 100, i, msg->payload); // Pattern file name + i += put_uint8_t_by_index(detected, i, msg->payload); // Accepted as true detection, 0 no, 1 yes + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a pattern_detected 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 pattern_detected C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pattern_detected_t* pattern_detected) +{ + return mavlink_msg_pattern_detected_pack(system_id, component_id, msg, pattern_detected->type, pattern_detected->confidence, pattern_detected->file, pattern_detected->detected); +} + +/** + * @brief Send a pattern_detected message + * @param chan MAVLink channel to send the message + * + * @param type 0: Pattern, 1: Letter + * @param confidence Confidence of detection + * @param file Pattern file name + * @param detected Accepted as true detection, 0 no, 1 yes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uint8_t type, float confidence, const int8_t* file, uint8_t detected) +{ + mavlink_message_t msg; + mavlink_msg_pattern_detected_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, confidence, file, detected); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE PATTERN_DETECTED UNPACKING + +/** + * @brief Get field type from pattern_detected message + * + * @return 0: Pattern, 1: Letter + */ +static inline uint8_t mavlink_msg_pattern_detected_get_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field confidence from pattern_detected message + * + * @return Confidence of detection + */ +static inline float mavlink_msg_pattern_detected_get_confidence(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 file from pattern_detected message + * + * @return Pattern file name + */ +static inline uint16_t mavlink_msg_pattern_detected_get_file(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(float), 100); + return 100; +} + +/** + * @brief Get field detected from pattern_detected message + * + * @return Accepted as true detection, 0 no, 1 yes + */ +static inline uint8_t mavlink_msg_pattern_detected_get_detected(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+100)[0]; +} + +/** + * @brief Decode a pattern_detected message into a struct + * + * @param msg The message to decode + * @param pattern_detected C-struct to decode the message contents into + */ +static inline void mavlink_msg_pattern_detected_decode(const mavlink_message_t* msg, mavlink_pattern_detected_t* pattern_detected) +{ + pattern_detected->type = mavlink_msg_pattern_detected_get_type(msg); + pattern_detected->confidence = mavlink_msg_pattern_detected_get_confidence(msg); + mavlink_msg_pattern_detected_get_file(msg, pattern_detected->file); + pattern_detected->detected = mavlink_msg_pattern_detected_get_detected(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_point_of_interest.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_point_of_interest.h new file mode 100644 index 0000000000000000000000000000000000000000..7e48c0fd913da62aa650594591bf7bda2faa7509 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_point_of_interest.h @@ -0,0 +1,241 @@ +// MESSAGE POINT_OF_INTEREST PACKING + +#define MAVLINK_MSG_ID_POINT_OF_INTEREST 161 + +typedef struct __mavlink_point_of_interest_t +{ + uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + uint8_t coordinate_system; ///< 0: global, 1:local + uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds + float x; ///< X Position + float y; ///< Y Position + float z; ///< Z Position + int8_t name[25]; ///< POI name + +} mavlink_point_of_interest_t; + +#define MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN 25 + + +/** + * @brief Pack a point_of_interest message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param name POI name + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const int8_t* name) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST; + + i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local + i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds + i += put_float_by_index(x, i, msg->payload); // X Position + i += put_float_by_index(y, i, msg->payload); // Y Position + i += put_float_by_index(z, i, msg->payload); // Z Position + i += put_array_by_index(name, 25, i, msg->payload); // POI name + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a point_of_interest 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 type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param name POI name + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const int8_t* name) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST; + + i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local + i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds + i += put_float_by_index(x, i, msg->payload); // X Position + i += put_float_by_index(y, i, msg->payload); // Y Position + i += put_float_by_index(z, i, msg->payload); // Z Position + i += put_array_by_index(name, 25, i, msg->payload); // POI name + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a point_of_interest 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 point_of_interest C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_point_of_interest_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_t* point_of_interest) +{ + return mavlink_msg_point_of_interest_pack(system_id, component_id, msg, point_of_interest->type, point_of_interest->color, point_of_interest->coordinate_system, point_of_interest->timeout, point_of_interest->x, point_of_interest->y, point_of_interest->z, point_of_interest->name); +} + +/** + * @brief Send a point_of_interest message + * @param chan MAVLink channel to send the message + * + * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param name POI name + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const int8_t* name) +{ + mavlink_message_t msg; + mavlink_msg_point_of_interest_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, color, coordinate_system, timeout, x, y, z, name); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POINT_OF_INTEREST UNPACKING + +/** + * @brief Get field type from point_of_interest message + * + * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + */ +static inline uint8_t mavlink_msg_point_of_interest_get_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field color from point_of_interest message + * + * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + */ +static inline uint8_t mavlink_msg_point_of_interest_get_color(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field coordinate_system from point_of_interest message + * + * @return 0: global, 1:local + */ +static inline uint8_t mavlink_msg_point_of_interest_get_coordinate_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field timeout from point_of_interest message + * + * @return 0: no timeout, >1: timeout in seconds + */ +static inline uint16_t mavlink_msg_point_of_interest_get_timeout(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 x from point_of_interest message + * + * @return X Position + */ +static inline float mavlink_msg_point_of_interest_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from point_of_interest message + * + * @return Y Position + */ +static inline float mavlink_msg_point_of_interest_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from point_of_interest message + * + * @return Z Position + */ +static inline float mavlink_msg_point_of_interest_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field name from point_of_interest message + * + * @return POI name + */ +static inline uint16_t mavlink_msg_point_of_interest_get_name(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float), 25); + return 25; +} + +/** + * @brief Decode a point_of_interest message into a struct + * + * @param msg The message to decode + * @param point_of_interest C-struct to decode the message contents into + */ +static inline void mavlink_msg_point_of_interest_decode(const mavlink_message_t* msg, mavlink_point_of_interest_t* point_of_interest) +{ + point_of_interest->type = mavlink_msg_point_of_interest_get_type(msg); + point_of_interest->color = mavlink_msg_point_of_interest_get_color(msg); + point_of_interest->coordinate_system = mavlink_msg_point_of_interest_get_coordinate_system(msg); + point_of_interest->timeout = mavlink_msg_point_of_interest_get_timeout(msg); + point_of_interest->x = mavlink_msg_point_of_interest_get_x(msg); + point_of_interest->y = mavlink_msg_point_of_interest_get_y(msg); + point_of_interest->z = mavlink_msg_point_of_interest_get_z(msg); + mavlink_msg_point_of_interest_get_name(msg, point_of_interest->name); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_point_of_interest_connection.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_point_of_interest_connection.h new file mode 100644 index 0000000000000000000000000000000000000000..fb3051746356ba92895d6a5f5c9d3635f8325bf3 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_point_of_interest_connection.h @@ -0,0 +1,307 @@ +// MESSAGE POINT_OF_INTEREST_CONNECTION PACKING + +#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION 162 + +typedef struct __mavlink_point_of_interest_connection_t +{ + uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + uint8_t coordinate_system; ///< 0: global, 1:local + uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds + float xp1; ///< X1 Position + float yp1; ///< Y1 Position + float zp1; ///< Z1 Position + float xp2; ///< X2 Position + float yp2; ///< Y2 Position + float zp2; ///< Z2 Position + int8_t name[25]; ///< POI connection name + +} mavlink_point_of_interest_connection_t; + +#define MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN 25 + + +/** + * @brief Pack a point_of_interest_connection message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param xp1 X1 Position + * @param yp1 Y1 Position + * @param zp1 Z1 Position + * @param xp2 X2 Position + * @param yp2 Y2 Position + * @param zp2 Z2 Position + * @param name POI connection name + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION; + + i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local + i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds + i += put_float_by_index(xp1, i, msg->payload); // X1 Position + i += put_float_by_index(yp1, i, msg->payload); // Y1 Position + i += put_float_by_index(zp1, i, msg->payload); // Z1 Position + i += put_float_by_index(xp2, i, msg->payload); // X2 Position + i += put_float_by_index(yp2, i, msg->payload); // Y2 Position + i += put_float_by_index(zp2, i, msg->payload); // Z2 Position + i += put_array_by_index(name, 25, i, msg->payload); // POI connection name + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a point_of_interest_connection 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 type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param xp1 X1 Position + * @param yp1 Y1 Position + * @param zp1 Z1 Position + * @param xp2 X2 Position + * @param yp2 Y2 Position + * @param zp2 Z2 Position + * @param name POI connection name + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION; + + i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local + i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds + i += put_float_by_index(xp1, i, msg->payload); // X1 Position + i += put_float_by_index(yp1, i, msg->payload); // Y1 Position + i += put_float_by_index(zp1, i, msg->payload); // Z1 Position + i += put_float_by_index(xp2, i, msg->payload); // X2 Position + i += put_float_by_index(yp2, i, msg->payload); // Y2 Position + i += put_float_by_index(zp2, i, msg->payload); // Z2 Position + i += put_array_by_index(name, 25, i, msg->payload); // POI connection name + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a point_of_interest_connection 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 point_of_interest_connection C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_point_of_interest_connection_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_connection_t* point_of_interest_connection) +{ + return mavlink_msg_point_of_interest_connection_pack(system_id, component_id, msg, point_of_interest_connection->type, point_of_interest_connection->color, point_of_interest_connection->coordinate_system, point_of_interest_connection->timeout, point_of_interest_connection->xp1, point_of_interest_connection->yp1, point_of_interest_connection->zp1, point_of_interest_connection->xp2, point_of_interest_connection->yp2, point_of_interest_connection->zp2, point_of_interest_connection->name); +} + +/** + * @brief Send a point_of_interest_connection message + * @param chan MAVLink channel to send the message + * + * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param xp1 X1 Position + * @param yp1 Y1 Position + * @param zp1 Z1 Position + * @param xp2 X2 Position + * @param yp2 Y2 Position + * @param zp2 Z2 Position + * @param name POI connection name + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name) +{ + mavlink_message_t msg; + mavlink_msg_point_of_interest_connection_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, color, coordinate_system, timeout, xp1, yp1, zp1, xp2, yp2, zp2, name); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POINT_OF_INTEREST_CONNECTION UNPACKING + +/** + * @brief Get field type from point_of_interest_connection message + * + * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + */ +static inline uint8_t mavlink_msg_point_of_interest_connection_get_type(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field color from point_of_interest_connection message + * + * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + */ +static inline uint8_t mavlink_msg_point_of_interest_connection_get_color(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field coordinate_system from point_of_interest_connection message + * + * @return 0: global, 1:local + */ +static inline uint8_t mavlink_msg_point_of_interest_connection_get_coordinate_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field timeout from point_of_interest_connection message + * + * @return 0: no timeout, >1: timeout in seconds + */ +static inline uint16_t mavlink_msg_point_of_interest_connection_get_timeout(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 xp1 from point_of_interest_connection message + * + * @return X1 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_xp1(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field yp1 from point_of_interest_connection message + * + * @return Y1 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_yp1(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field zp1 from point_of_interest_connection message + * + * @return Z1 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_zp1(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field xp2 from point_of_interest_connection message + * + * @return X2 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_xp2(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yp2 from point_of_interest_connection message + * + * @return Y2 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_yp2(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field zp2 from point_of_interest_connection message + * + * @return Z2 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_zp2(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field name from point_of_interest_connection message + * + * @return POI connection name + */ +static inline uint16_t mavlink_msg_point_of_interest_connection_get_name(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float), 25); + return 25; +} + +/** + * @brief Decode a point_of_interest_connection message into a struct + * + * @param msg The message to decode + * @param point_of_interest_connection C-struct to decode the message contents into + */ +static inline void mavlink_msg_point_of_interest_connection_decode(const mavlink_message_t* msg, mavlink_point_of_interest_connection_t* point_of_interest_connection) +{ + point_of_interest_connection->type = mavlink_msg_point_of_interest_connection_get_type(msg); + point_of_interest_connection->color = mavlink_msg_point_of_interest_connection_get_color(msg); + point_of_interest_connection->coordinate_system = mavlink_msg_point_of_interest_connection_get_coordinate_system(msg); + point_of_interest_connection->timeout = mavlink_msg_point_of_interest_connection_get_timeout(msg); + point_of_interest_connection->xp1 = mavlink_msg_point_of_interest_connection_get_xp1(msg); + point_of_interest_connection->yp1 = mavlink_msg_point_of_interest_connection_get_yp1(msg); + point_of_interest_connection->zp1 = mavlink_msg_point_of_interest_connection_get_zp1(msg); + point_of_interest_connection->xp2 = mavlink_msg_point_of_interest_connection_get_xp2(msg); + point_of_interest_connection->yp2 = mavlink_msg_point_of_interest_connection_get_yp2(msg); + point_of_interest_connection->zp2 = mavlink_msg_point_of_interest_connection_get_zp2(msg); + mavlink_msg_point_of_interest_connection_get_name(msg, point_of_interest_connection->name); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_position_control_offset_set.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_position_control_offset_set.h new file mode 100644 index 0000000000000000000000000000000000000000..30f076bba896df52d847ad3b19b6b65ae4dafc7c --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_position_control_offset_set.h @@ -0,0 +1,206 @@ +// MESSAGE POSITION_CONTROL_OFFSET_SET PACKING + +#define MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET 154 + +typedef struct __mavlink_position_control_offset_set_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + float x; ///< x position offset + float y; ///< y position offset + float z; ///< z position offset + float yaw; ///< yaw orientation offset in radians, 0 = NORTH + +} mavlink_position_control_offset_set_t; + + + +/** + * @brief Pack a position_control_offset_set message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param x x position offset + * @param y y position offset + * @param z z position offset + * @param yaw yaw orientation offset in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_offset_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET; + + 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_float_by_index(x, i, msg->payload); // x position offset + i += put_float_by_index(y, i, msg->payload); // y position offset + i += put_float_by_index(z, i, msg->payload); // z position offset + i += put_float_by_index(yaw, i, msg->payload); // yaw orientation offset in radians, 0 = NORTH + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a position_control_offset_set 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 System ID + * @param target_component Component ID + * @param x x position offset + * @param y y position offset + * @param z z position offset + * @param yaw yaw orientation offset in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_offset_set_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 x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET; + + 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_float_by_index(x, i, msg->payload); // x position offset + i += put_float_by_index(y, i, msg->payload); // y position offset + i += put_float_by_index(z, i, msg->payload); // z position offset + i += put_float_by_index(yaw, i, msg->payload); // yaw orientation offset in radians, 0 = NORTH + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a position_control_offset_set 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 position_control_offset_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_control_offset_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_offset_set_t* position_control_offset_set) +{ + return mavlink_msg_position_control_offset_set_pack(system_id, component_id, msg, position_control_offset_set->target_system, position_control_offset_set->target_component, position_control_offset_set->x, position_control_offset_set->y, position_control_offset_set->z, position_control_offset_set->yaw); +} + +/** + * @brief Send a position_control_offset_set message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param x x position offset + * @param y y position offset + * @param z z position offset + * @param yaw yaw orientation offset in radians, 0 = NORTH + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_control_offset_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_position_control_offset_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POSITION_CONTROL_OFFSET_SET UNPACKING + +/** + * @brief Get field target_system from position_control_offset_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_position_control_offset_set_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from position_control_offset_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_position_control_offset_set_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field x from position_control_offset_set message + * + * @return x position offset + */ +static inline float mavlink_msg_position_control_offset_set_get_x(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 y from position_control_offset_set message + * + * @return y position offset + */ +static inline float mavlink_msg_position_control_offset_set_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from position_control_offset_set message + * + * @return z position offset + */ +static inline float mavlink_msg_position_control_offset_set_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from position_control_offset_set message + * + * @return yaw orientation offset in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_control_offset_set_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a position_control_offset_set message into a struct + * + * @param msg The message to decode + * @param position_control_offset_set C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_control_offset_set_decode(const mavlink_message_t* msg, mavlink_position_control_offset_set_t* position_control_offset_set) +{ + position_control_offset_set->target_system = mavlink_msg_position_control_offset_set_get_target_system(msg); + position_control_offset_set->target_component = mavlink_msg_position_control_offset_set_get_target_component(msg); + position_control_offset_set->x = mavlink_msg_position_control_offset_set_get_x(msg); + position_control_offset_set->y = mavlink_msg_position_control_offset_set_get_y(msg); + position_control_offset_set->z = mavlink_msg_position_control_offset_set_get_z(msg); + position_control_offset_set->yaw = mavlink_msg_position_control_offset_set_get_yaw(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint.h new file mode 100644 index 0000000000000000000000000000000000000000..59bcb131ce5e0e1c8e08a32145f99147144ee7ba --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint.h @@ -0,0 +1,192 @@ +// MESSAGE POSITION_CONTROL_SETPOINT PACKING + +#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT 121 + +typedef struct __mavlink_position_control_setpoint_t +{ + uint16_t id; ///< ID of waypoint, 0 for plain position + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< yaw orientation in radians, 0 = NORTH + +} mavlink_position_control_setpoint_t; + + + +/** + * @brief Pack a position_control_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; + + i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position + i += put_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a position_control_setpoint 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 id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; + + i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position + i += put_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a position_control_setpoint 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 position_control_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_control_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_t* position_control_setpoint) +{ + return mavlink_msg_position_control_setpoint_pack(system_id, component_id, msg, position_control_setpoint->id, position_control_setpoint->x, position_control_setpoint->y, position_control_setpoint->z, position_control_setpoint->yaw); +} + +/** + * @brief Send a position_control_setpoint message + * @param chan MAVLink channel to send the message + * + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_position_control_setpoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, id, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POSITION_CONTROL_SETPOINT UNPACKING + +/** + * @brief Get field id from position_control_setpoint message + * + * @return ID of waypoint, 0 for plain position + */ +static inline uint16_t mavlink_msg_position_control_setpoint_get_id(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 x from position_control_setpoint message + * + * @return x position + */ +static inline float mavlink_msg_position_control_setpoint_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from position_control_setpoint message + * + * @return y position + */ +static inline float mavlink_msg_position_control_setpoint_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from position_control_setpoint message + * + * @return z position + */ +static inline float mavlink_msg_position_control_setpoint_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from position_control_setpoint message + * + * @return yaw orientation in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_control_setpoint_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a position_control_setpoint message into a struct + * + * @param msg The message to decode + * @param position_control_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_control_setpoint_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_t* position_control_setpoint) +{ + position_control_setpoint->id = mavlink_msg_position_control_setpoint_get_id(msg); + position_control_setpoint->x = mavlink_msg_position_control_setpoint_get_x(msg); + position_control_setpoint->y = mavlink_msg_position_control_setpoint_get_y(msg); + position_control_setpoint->z = mavlink_msg_position_control_setpoint_get_z(msg); + position_control_setpoint->yaw = mavlink_msg_position_control_setpoint_get_yaw(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h new file mode 100644 index 0000000000000000000000000000000000000000..75150e66b9aab096b8cac43183d2996a6f8a919f --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h @@ -0,0 +1,226 @@ +// MESSAGE POSITION_CONTROL_SETPOINT_SET PACKING + +#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET 120 + +typedef struct __mavlink_position_control_setpoint_set_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint16_t id; ///< ID of waypoint, 0 for plain position + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< yaw orientation in radians, 0 = NORTH + +} mavlink_position_control_setpoint_set_t; + + + +/** + * @brief Pack a position_control_setpoint_set message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET; + + 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_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position + i += put_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a position_control_setpoint_set 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 System ID + * @param target_component Component ID + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_setpoint_set_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 id, float x, float y, float z, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET; + + 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_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position + i += put_float_by_index(x, i, msg->payload); // x position + i += put_float_by_index(y, i, msg->payload); // y position + i += put_float_by_index(z, i, msg->payload); // z position + i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a position_control_setpoint_set 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 position_control_setpoint_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_control_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_set_t* position_control_setpoint_set) +{ + return mavlink_msg_position_control_setpoint_set_pack(system_id, component_id, msg, position_control_setpoint_set->target_system, position_control_setpoint_set->target_component, position_control_setpoint_set->id, position_control_setpoint_set->x, position_control_setpoint_set->y, position_control_setpoint_set->z, position_control_setpoint_set->yaw); +} + +/** + * @brief Send a position_control_setpoint_set message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_control_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_position_control_setpoint_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, id, x, y, z, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE POSITION_CONTROL_SETPOINT_SET UNPACKING + +/** + * @brief Get field target_system from position_control_setpoint_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_system(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field target_component from position_control_setpoint_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_component(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field id from position_control_setpoint_set message + * + * @return ID of waypoint, 0 for plain position + */ +static inline uint16_t mavlink_msg_position_control_setpoint_set_get_id(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 Get field x from position_control_setpoint_set message + * + * @return x position + */ +static inline float mavlink_msg_position_control_setpoint_set_get_x(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field y from position_control_setpoint_set message + * + * @return y position + */ +static inline float mavlink_msg_position_control_setpoint_set_get_y(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field z from position_control_setpoint_set message + * + * @return z position + */ +static inline float mavlink_msg_position_control_setpoint_set_get_z(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from position_control_setpoint_set message + * + * @return yaw orientation in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_control_setpoint_set_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a position_control_setpoint_set message into a struct + * + * @param msg The message to decode + * @param position_control_setpoint_set C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_control_setpoint_set_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_set_t* position_control_setpoint_set) +{ + position_control_setpoint_set->target_system = mavlink_msg_position_control_setpoint_set_get_target_system(msg); + position_control_setpoint_set->target_component = mavlink_msg_position_control_setpoint_set_get_target_component(msg); + position_control_setpoint_set->id = mavlink_msg_position_control_setpoint_set_get_id(msg); + position_control_setpoint_set->x = mavlink_msg_position_control_setpoint_set_get_x(msg); + position_control_setpoint_set->y = mavlink_msg_position_control_setpoint_set_get_y(msg); + position_control_setpoint_set->z = mavlink_msg_position_control_setpoint_set_get_z(msg); + position_control_setpoint_set->yaw = mavlink_msg_position_control_setpoint_set_get_yaw(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_raw_aux.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_raw_aux.h new file mode 100644 index 0000000000000000000000000000000000000000..61adee29708d3814ad5d24496170ffae4876991b --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_raw_aux.h @@ -0,0 +1,226 @@ +// MESSAGE RAW_AUX PACKING + +#define MAVLINK_MSG_ID_RAW_AUX 141 + +typedef struct __mavlink_raw_aux_t +{ + uint16_t adc1; ///< ADC1 (J405 ADC3, LPC2148 AD0.6) + uint16_t adc2; ///< ADC2 (J405 ADC5, LPC2148 AD0.2) + uint16_t adc3; ///< ADC3 (J405 ADC6, LPC2148 AD0.1) + uint16_t adc4; ///< ADC4 (J405 ADC7, LPC2148 AD1.3) + uint16_t vbat; ///< Battery voltage + int16_t temp; ///< Temperature (degrees celcius) + int32_t baro; ///< Barometric pressure (hecto Pascal) + +} mavlink_raw_aux_t; + + + +/** + * @brief Pack a raw_aux 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 adc1 ADC1 (J405 ADC3, LPC2148 AD0.6) + * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2) + * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1) + * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3) + * @param vbat Battery voltage + * @param temp Temperature (degrees celcius) + * @param baro Barometric pressure (hecto Pascal) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RAW_AUX; + + i += put_uint16_t_by_index(adc1, i, msg->payload); // ADC1 (J405 ADC3, LPC2148 AD0.6) + i += put_uint16_t_by_index(adc2, i, msg->payload); // ADC2 (J405 ADC5, LPC2148 AD0.2) + i += put_uint16_t_by_index(adc3, i, msg->payload); // ADC3 (J405 ADC6, LPC2148 AD0.1) + i += put_uint16_t_by_index(adc4, i, msg->payload); // ADC4 (J405 ADC7, LPC2148 AD1.3) + i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage + i += put_int16_t_by_index(temp, i, msg->payload); // Temperature (degrees celcius) + i += put_int32_t_by_index(baro, i, msg->payload); // Barometric pressure (hecto Pascal) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a raw_aux 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 adc1 ADC1 (J405 ADC3, LPC2148 AD0.6) + * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2) + * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1) + * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3) + * @param vbat Battery voltage + * @param temp Temperature (degrees celcius) + * @param baro Barometric pressure (hecto Pascal) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RAW_AUX; + + i += put_uint16_t_by_index(adc1, i, msg->payload); // ADC1 (J405 ADC3, LPC2148 AD0.6) + i += put_uint16_t_by_index(adc2, i, msg->payload); // ADC2 (J405 ADC5, LPC2148 AD0.2) + i += put_uint16_t_by_index(adc3, i, msg->payload); // ADC3 (J405 ADC6, LPC2148 AD0.1) + i += put_uint16_t_by_index(adc4, i, msg->payload); // ADC4 (J405 ADC7, LPC2148 AD1.3) + i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage + i += put_int16_t_by_index(temp, i, msg->payload); // Temperature (degrees celcius) + i += put_int32_t_by_index(baro, i, msg->payload); // Barometric pressure (hecto Pascal) + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a raw_aux 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 raw_aux C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux) +{ + return mavlink_msg_raw_aux_pack(system_id, component_id, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro); +} + +/** + * @brief Send a raw_aux message + * @param chan MAVLink channel to send the message + * + * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6) + * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2) + * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1) + * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3) + * @param vbat Battery voltage + * @param temp Temperature (degrees celcius) + * @param baro Barometric pressure (hecto Pascal) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) +{ + mavlink_message_t msg; + mavlink_msg_raw_aux_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, adc1, adc2, adc3, adc4, vbat, temp, baro); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RAW_AUX UNPACKING + +/** + * @brief Get field adc1 from raw_aux message + * + * @return ADC1 (J405 ADC3, LPC2148 AD0.6) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc1(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 adc2 from raw_aux message + * + * @return ADC2 (J405 ADC5, LPC2148 AD0.2) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc2(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 adc3 from raw_aux message + * + * @return ADC3 (J405 ADC6, LPC2148 AD0.1) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc3(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 adc4 from raw_aux message + * + * @return ADC4 (J405 ADC7, LPC2148 AD1.3) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc4(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 vbat from raw_aux message + * + * @return Battery voltage + */ +static inline uint16_t mavlink_msg_raw_aux_get_vbat(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; +} + +/** + * @brief Get field temp from raw_aux message + * + * @return Temperature (degrees celcius) + */ +static inline int16_t mavlink_msg_raw_aux_get_temp(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)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field baro from raw_aux message + * + * @return Barometric pressure (hecto Pascal) + */ +static inline int32_t mavlink_msg_raw_aux_get_baro(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(int16_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Decode a raw_aux message into a struct + * + * @param msg The message to decode + * @param raw_aux C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_aux_decode(const mavlink_message_t* msg, mavlink_raw_aux_t* raw_aux) +{ + raw_aux->adc1 = mavlink_msg_raw_aux_get_adc1(msg); + raw_aux->adc2 = mavlink_msg_raw_aux_get_adc2(msg); + raw_aux->adc3 = mavlink_msg_raw_aux_get_adc3(msg); + raw_aux->adc4 = mavlink_msg_raw_aux_get_adc4(msg); + raw_aux->vbat = mavlink_msg_raw_aux_get_vbat(msg); + raw_aux->temp = mavlink_msg_raw_aux_get_temp(msg); + raw_aux->baro = mavlink_msg_raw_aux_get_baro(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_set_cam_shutter.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_set_cam_shutter.h new file mode 100644 index 0000000000000000000000000000000000000000..6a34b7e4bd3c97d9990a32b71f5ce42a1736301b --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_set_cam_shutter.h @@ -0,0 +1,197 @@ +// MESSAGE SET_CAM_SHUTTER PACKING + +#define MAVLINK_MSG_ID_SET_CAM_SHUTTER 100 + +typedef struct __mavlink_set_cam_shutter_t +{ + uint8_t cam_no; ///< Camera id + uint8_t cam_mode; ///< Camera mode: 0 = auto, 1 = manual + uint8_t trigger_pin; ///< Trigger pin, 0-3 for PtGrey FireFly + uint16_t interval; ///< Shutter interval, in microseconds + uint16_t exposure; ///< Exposure time, in microseconds + float gain; ///< Camera gain + +} mavlink_set_cam_shutter_t; + + + +/** + * @brief Pack a set_cam_shutter 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 cam_no Camera id + * @param cam_mode Camera mode: 0 = auto, 1 = manual + * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly + * @param interval Shutter interval, in microseconds + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER; + + i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera id + i += put_uint8_t_by_index(cam_mode, i, msg->payload); // Camera mode: 0 = auto, 1 = manual + i += put_uint8_t_by_index(trigger_pin, i, msg->payload); // Trigger pin, 0-3 for PtGrey FireFly + i += put_uint16_t_by_index(interval, i, msg->payload); // Shutter interval, in microseconds + i += put_uint16_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds + i += put_float_by_index(gain, i, msg->payload); // Camera gain + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a set_cam_shutter 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 cam_no Camera id + * @param cam_mode Camera mode: 0 = auto, 1 = manual + * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly + * @param interval Shutter interval, in microseconds + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER; + + i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera id + i += put_uint8_t_by_index(cam_mode, i, msg->payload); // Camera mode: 0 = auto, 1 = manual + i += put_uint8_t_by_index(trigger_pin, i, msg->payload); // Trigger pin, 0-3 for PtGrey FireFly + i += put_uint16_t_by_index(interval, i, msg->payload); // Shutter interval, in microseconds + i += put_uint16_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds + i += put_float_by_index(gain, i, msg->payload); // Camera gain + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a set_cam_shutter 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 set_cam_shutter C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_cam_shutter_t* set_cam_shutter) +{ + return mavlink_msg_set_cam_shutter_pack(system_id, component_id, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain); +} + +/** + * @brief Send a set_cam_shutter message + * @param chan MAVLink channel to send the message + * + * @param cam_no Camera id + * @param cam_mode Camera mode: 0 = auto, 1 = manual + * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly + * @param interval Shutter interval, in microseconds + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) +{ + mavlink_message_t msg; + mavlink_msg_set_cam_shutter_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_no, cam_mode, trigger_pin, interval, exposure, gain); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SET_CAM_SHUTTER UNPACKING + +/** + * @brief Get field cam_no from set_cam_shutter message + * + * @return Camera id + */ +static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_no(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field cam_mode from set_cam_shutter message + * + * @return Camera mode: 0 = auto, 1 = manual + */ +static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_mode(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field trigger_pin from set_cam_shutter message + * + * @return Trigger pin, 0-3 for PtGrey FireFly + */ +static inline uint8_t mavlink_msg_set_cam_shutter_get_trigger_pin(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field interval from set_cam_shutter message + * + * @return Shutter interval, in microseconds + */ +static inline uint16_t mavlink_msg_set_cam_shutter_get_interval(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 exposure from set_cam_shutter message + * + * @return Exposure time, in microseconds + */ +static inline uint16_t mavlink_msg_set_cam_shutter_get_exposure(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field gain from set_cam_shutter message + * + * @return Camera gain + */ +static inline float mavlink_msg_set_cam_shutter_get_gain(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[3]; + return (float)r.f; +} + +/** + * @brief Decode a set_cam_shutter message into a struct + * + * @param msg The message to decode + * @param set_cam_shutter C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_cam_shutter_decode(const mavlink_message_t* msg, mavlink_set_cam_shutter_t* set_cam_shutter) +{ + set_cam_shutter->cam_no = mavlink_msg_set_cam_shutter_get_cam_no(msg); + set_cam_shutter->cam_mode = mavlink_msg_set_cam_shutter_get_cam_mode(msg); + set_cam_shutter->trigger_pin = mavlink_msg_set_cam_shutter_get_trigger_pin(msg); + set_cam_shutter->interval = mavlink_msg_set_cam_shutter_get_interval(msg); + set_cam_shutter->exposure = mavlink_msg_set_cam_shutter_get_exposure(msg); + set_cam_shutter->gain = mavlink_msg_set_cam_shutter_get_gain(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h new file mode 100644 index 0000000000000000000000000000000000000000..6e349eafc55eaaca92c6ec4a3a5e86dfdce8bb91 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_vicon_position_estimate.h @@ -0,0 +1,242 @@ +// MESSAGE VICON_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 112 + +typedef struct __mavlink_vicon_position_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float x; ///< Global X position + float y; ///< Global Y position + float z; ///< Global Z position + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad + +} mavlink_vicon_position_estimate_t; + + + +/** + * @brief Pack a vicon_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds) + i += put_float_by_index(x, i, msg->payload); // Global X position + i += put_float_by_index(y, i, msg->payload); // Global Y position + i += put_float_by_index(z, i, msg->payload); // Global Z position + i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a vicon_position_estimate 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 usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds) + i += put_float_by_index(x, i, msg->payload); // Global X position + i += put_float_by_index(y, i, msg->payload); // Global Y position + i += put_float_by_index(z, i, msg->payload); // Global Z position + i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a vicon_position_estimate 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 vicon_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ + return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); +} + +/** + * @brief Send a vicon_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_vicon_position_estimate_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z, roll, pitch, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE VICON_POSITION_ESTIMATE UNPACKING + +/** + * @brief Get field usec from vicon_position_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field x from vicon_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vicon_position_estimate_get_x(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; +} + +/** + * @brief Get field y from vicon_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vicon_position_estimate_get_y(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; +} + +/** + * @brief Get field z from vicon_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vicon_position_estimate_get_z(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; +} + +/** + * @brief Get field roll from vicon_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from vicon_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from vicon_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a vicon_position_estimate message into a struct + * + * @param msg The message to decode + * @param vicon_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ + vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg); + vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg); + vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg); + vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg); + vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg); + vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg); + vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_vision_position_estimate.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_vision_position_estimate.h new file mode 100644 index 0000000000000000000000000000000000000000..30728191d4a45423c65544c3dd16e409bf7809cc --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_vision_position_estimate.h @@ -0,0 +1,242 @@ +// MESSAGE VISION_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 111 + +typedef struct __mavlink_vision_position_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float x; ///< Global X position + float y; ///< Global Y position + float z; ///< Global Z position + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad + +} mavlink_vision_position_estimate_t; + + + +/** + * @brief Pack a vision_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds) + i += put_float_by_index(x, i, msg->payload); // Global X position + i += put_float_by_index(y, i, msg->payload); // Global Y position + i += put_float_by_index(z, i, msg->payload); // Global Z position + i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a vision_position_estimate 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 usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds) + i += put_float_by_index(x, i, msg->payload); // Global X position + i += put_float_by_index(y, i, msg->payload); // Global Y position + i += put_float_by_index(z, i, msg->payload); // Global Z position + i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad + i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad + i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a vision_position_estimate 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 vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) +{ + return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); +} + +/** + * @brief Send a vision_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ + mavlink_message_t msg; + mavlink_msg_vision_position_estimate_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z, roll, pitch, yaw); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE VISION_POSITION_ESTIMATE UNPACKING + +/** + * @brief Get field usec from vision_position_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field x from vision_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vision_position_estimate_get_x(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; +} + +/** + * @brief Get field y from vision_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vision_position_estimate_get_y(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; +} + +/** + * @brief Get field z from vision_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vision_position_estimate_get_z(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; +} + +/** + * @brief Get field roll from vision_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field pitch from vision_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field yaw from vision_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a vision_position_estimate message into a struct + * + * @param msg The message to decode + * @param vision_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate) +{ + vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg); + vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg); + vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg); + vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg); + vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg); + vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg); + vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_command.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_command.h new file mode 100644 index 0000000000000000000000000000000000000000..25ea0f5f1de38eca19fb1da9b67d7ed4d3ba4596 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_command.h @@ -0,0 +1,158 @@ +// MESSAGE WATCHDOG_COMMAND PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_COMMAND 153 + +typedef struct __mavlink_watchdog_command_t +{ + uint8_t target_system_id; ///< Target system ID + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_id; ///< Process ID + uint8_t command_id; ///< Command ID + +} mavlink_watchdog_command_t; + + + +/** + * @brief Pack a watchdog_command 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_id Target system ID + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param command_id Command ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; + + i += put_uint8_t_by_index(target_system_id, i, msg->payload); // Target system ID + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID + i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID + i += put_uint8_t_by_index(command_id, i, msg->payload); // Command ID + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a watchdog_command 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_id Target system ID + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param command_id Command ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; + + i += put_uint8_t_by_index(target_system_id, i, msg->payload); // Target system ID + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID + i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID + i += put_uint8_t_by_index(command_id, i, msg->payload); // Command ID + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a watchdog_command 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 watchdog_command C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command) +{ + return mavlink_msg_watchdog_command_pack(system_id, component_id, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id); +} + +/** + * @brief Send a watchdog_command message + * @param chan MAVLink channel to send the message + * + * @param target_system_id Target system ID + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param command_id Command ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) +{ + mavlink_message_t msg; + mavlink_msg_watchdog_command_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system_id, watchdog_id, process_id, command_id); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WATCHDOG_COMMAND UNPACKING + +/** + * @brief Get field target_system_id from watchdog_command message + * + * @return Target system ID + */ +static inline uint8_t mavlink_msg_watchdog_command_get_target_system_id(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field watchdog_id from watchdog_command message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_command_get_watchdog_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field process_id from watchdog_command message + * + * @return Process ID + */ +static inline uint16_t mavlink_msg_watchdog_command_get_process_id(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint16_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Get field command_id from watchdog_command message + * + * @return Command ID + */ +static inline uint8_t mavlink_msg_watchdog_command_get_command_id(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; +} + +/** + * @brief Decode a watchdog_command message into a struct + * + * @param msg The message to decode + * @param watchdog_command C-struct to decode the message contents into + */ +static inline void mavlink_msg_watchdog_command_decode(const mavlink_message_t* msg, mavlink_watchdog_command_t* watchdog_command) +{ + watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg); + watchdog_command->watchdog_id = mavlink_msg_watchdog_command_get_watchdog_id(msg); + watchdog_command->process_id = mavlink_msg_watchdog_command_get_process_id(msg); + watchdog_command->command_id = mavlink_msg_watchdog_command_get_command_id(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h new file mode 100644 index 0000000000000000000000000000000000000000..db693bc554069e8fa22624b64e8c5bb4e35aef2d --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h @@ -0,0 +1,124 @@ +// MESSAGE WATCHDOG_HEARTBEAT PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT 150 + +typedef struct __mavlink_watchdog_heartbeat_t +{ + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_count; ///< Number of processes + +} mavlink_watchdog_heartbeat_t; + + + +/** + * @brief Pack a watchdog_heartbeat message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param watchdog_id Watchdog ID + * @param process_count Number of processes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_count) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT; + + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID + i += put_uint16_t_by_index(process_count, i, msg->payload); // Number of processes + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a watchdog_heartbeat 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 watchdog_id Watchdog ID + * @param process_count Number of processes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_count) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT; + + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID + i += put_uint16_t_by_index(process_count, i, msg->payload); // Number of processes + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a watchdog_heartbeat 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 watchdog_heartbeat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_heartbeat_t* watchdog_heartbeat) +{ + return mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count); +} + +/** + * @brief Send a watchdog_heartbeat message + * @param chan MAVLink channel to send the message + * + * @param watchdog_id Watchdog ID + * @param process_count Number of processes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count) +{ + mavlink_message_t msg; + mavlink_msg_watchdog_heartbeat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_count); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WATCHDOG_HEARTBEAT UNPACKING + +/** + * @brief Get field watchdog_id from watchdog_heartbeat message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_get_watchdog_id(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 process_count from watchdog_heartbeat message + * + * @return Number of processes + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_get_process_count(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 Decode a watchdog_heartbeat message into a struct + * + * @param msg The message to decode + * @param watchdog_heartbeat C-struct to decode the message contents into + */ +static inline void mavlink_msg_watchdog_heartbeat_decode(const mavlink_message_t* msg, mavlink_watchdog_heartbeat_t* watchdog_heartbeat) +{ + watchdog_heartbeat->watchdog_id = mavlink_msg_watchdog_heartbeat_get_watchdog_id(msg); + watchdog_heartbeat->process_count = mavlink_msg_watchdog_heartbeat_get_process_count(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_process_info.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_process_info.h new file mode 100644 index 0000000000000000000000000000000000000000..a312a14679fb7589f6eaa81c19df0922bf3d9444 --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_process_info.h @@ -0,0 +1,186 @@ +// MESSAGE WATCHDOG_PROCESS_INFO PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO 151 + +typedef struct __mavlink_watchdog_process_info_t +{ + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_id; ///< Process ID + int8_t name[100]; ///< Process name + int8_t arguments[147]; ///< Process arguments + int32_t timeout; ///< Timeout (seconds) + +} mavlink_watchdog_process_info_t; + +#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_NAME_LEN 100 +#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_ARGUMENTS_LEN 147 + + +/** + * @brief Pack a watchdog_process_info 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 watchdog_id Watchdog ID + * @param process_id Process ID + * @param name Process name + * @param arguments Process arguments + * @param timeout Timeout (seconds) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO; + + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID + i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID + i += put_array_by_index(name, 100, i, msg->payload); // Process name + i += put_array_by_index(arguments, 147, i, msg->payload); // Process arguments + i += put_int32_t_by_index(timeout, i, msg->payload); // Timeout (seconds) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a watchdog_process_info 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 watchdog_id Watchdog ID + * @param process_id Process ID + * @param name Process name + * @param arguments Process arguments + * @param timeout Timeout (seconds) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO; + + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID + i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID + i += put_array_by_index(name, 100, i, msg->payload); // Process name + i += put_array_by_index(arguments, 147, i, msg->payload); // Process arguments + i += put_int32_t_by_index(timeout, i, msg->payload); // Timeout (seconds) + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a watchdog_process_info 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 watchdog_process_info C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_info_t* watchdog_process_info) +{ + return mavlink_msg_watchdog_process_info_pack(system_id, component_id, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout); +} + +/** + * @brief Send a watchdog_process_info message + * @param chan MAVLink channel to send the message + * + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param name Process name + * @param arguments Process arguments + * @param timeout Timeout (seconds) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const int8_t* name, const int8_t* arguments, int32_t timeout) +{ + mavlink_message_t msg; + mavlink_msg_watchdog_process_info_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_id, name, arguments, timeout); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WATCHDOG_PROCESS_INFO UNPACKING + +/** + * @brief Get field watchdog_id from watchdog_process_info message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_watchdog_id(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 process_id from watchdog_process_info message + * + * @return Process ID + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_process_id(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 name from watchdog_process_info message + * + * @return Process name + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint16_t)+sizeof(uint16_t), 100); + return 100; +} + +/** + * @brief Get field arguments from watchdog_process_info message + * + * @return Process arguments + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_arguments(const mavlink_message_t* msg, int8_t* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100, 147); + return 147; +} + +/** + * @brief Get field timeout from watchdog_process_info message + * + * @return Timeout (seconds) + */ +static inline int32_t mavlink_msg_watchdog_process_info_get_timeout(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+100+147)[3]; + return (int32_t)r.i; +} + +/** + * @brief Decode a watchdog_process_info message into a struct + * + * @param msg The message to decode + * @param watchdog_process_info C-struct to decode the message contents into + */ +static inline void mavlink_msg_watchdog_process_info_decode(const mavlink_message_t* msg, mavlink_watchdog_process_info_t* watchdog_process_info) +{ + watchdog_process_info->watchdog_id = mavlink_msg_watchdog_process_info_get_watchdog_id(msg); + watchdog_process_info->process_id = mavlink_msg_watchdog_process_info_get_process_id(msg); + mavlink_msg_watchdog_process_info_get_name(msg, watchdog_process_info->name); + mavlink_msg_watchdog_process_info_get_arguments(msg, watchdog_process_info->arguments); + watchdog_process_info->timeout = mavlink_msg_watchdog_process_info_get_timeout(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_process_status.h b/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_process_status.h new file mode 100644 index 0000000000000000000000000000000000000000..9afa6ca14af95e685c5aa606eb47c6b11c708ace --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/mavlink_msg_watchdog_process_status.h @@ -0,0 +1,200 @@ +// MESSAGE WATCHDOG_PROCESS_STATUS PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS 152 + +typedef struct __mavlink_watchdog_process_status_t +{ + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_id; ///< Process ID + uint8_t state; ///< Is running / finished / suspended / crashed + uint8_t muted; ///< Is muted + int32_t pid; ///< PID + uint16_t crashes; ///< Number of crashes + +} mavlink_watchdog_process_status_t; + + + +/** + * @brief Pack a watchdog_process_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param state Is running / finished / suspended / crashed + * @param muted Is muted + * @param pid PID + * @param crashes Number of crashes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS; + + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID + i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID + i += put_uint8_t_by_index(state, i, msg->payload); // Is running / finished / suspended / crashed + i += put_uint8_t_by_index(muted, i, msg->payload); // Is muted + i += put_int32_t_by_index(pid, i, msg->payload); // PID + i += put_uint16_t_by_index(crashes, i, msg->payload); // Number of crashes + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a watchdog_process_status 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 watchdog_id Watchdog ID + * @param process_id Process ID + * @param state Is running / finished / suspended / crashed + * @param muted Is muted + * @param pid PID + * @param crashes Number of crashes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS; + + i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID + i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID + i += put_uint8_t_by_index(state, i, msg->payload); // Is running / finished / suspended / crashed + i += put_uint8_t_by_index(muted, i, msg->payload); // Is muted + i += put_int32_t_by_index(pid, i, msg->payload); // PID + i += put_uint16_t_by_index(crashes, i, msg->payload); // Number of crashes + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a watchdog_process_status 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 watchdog_process_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status) +{ + return mavlink_msg_watchdog_process_status_pack(system_id, component_id, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes); +} + +/** + * @brief Send a watchdog_process_status message + * @param chan MAVLink channel to send the message + * + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param state Is running / finished / suspended / crashed + * @param muted Is muted + * @param pid PID + * @param crashes Number of crashes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) +{ + mavlink_message_t msg; + mavlink_msg_watchdog_process_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, watchdog_id, process_id, state, muted, pid, crashes); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE WATCHDOG_PROCESS_STATUS UNPACKING + +/** + * @brief Get field watchdog_id from watchdog_process_status message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_process_status_get_watchdog_id(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 process_id from watchdog_process_status message + * + * @return Process ID + */ +static inline uint16_t mavlink_msg_watchdog_process_status_get_process_id(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 state from watchdog_process_status message + * + * @return Is running / finished / suspended / crashed + */ +static inline uint8_t mavlink_msg_watchdog_process_status_get_state(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0]; +} + +/** + * @brief Get field muted from watchdog_process_status message + * + * @return Is muted + */ +static inline uint8_t mavlink_msg_watchdog_process_status_get_muted(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field pid from watchdog_process_status message + * + * @return PID + */ +static inline int32_t mavlink_msg_watchdog_process_status_get_pid(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; + r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[1]; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[2]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[3]; + return (int32_t)r.i; +} + +/** + * @brief Get field crashes from watchdog_process_status message + * + * @return Number of crashes + */ +static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[0]; + r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[1]; + return (uint16_t)r.s; +} + +/** + * @brief Decode a watchdog_process_status message into a struct + * + * @param msg The message to decode + * @param watchdog_process_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_watchdog_process_status_decode(const mavlink_message_t* msg, mavlink_watchdog_process_status_t* watchdog_process_status) +{ + watchdog_process_status->watchdog_id = mavlink_msg_watchdog_process_status_get_watchdog_id(msg); + watchdog_process_status->process_id = mavlink_msg_watchdog_process_status_get_process_id(msg); + watchdog_process_status->state = mavlink_msg_watchdog_process_status_get_state(msg); + watchdog_process_status->muted = mavlink_msg_watchdog_process_status_get_muted(msg); + watchdog_process_status->pid = mavlink_msg_watchdog_process_status_get_pid(msg); + watchdog_process_status->crashes = mavlink_msg_watchdog_process_status_get_crashes(msg); +} diff --git a/thirdParty/mavlink/include/pixhawk/pixhawk.h b/thirdParty/mavlink/include/pixhawk/pixhawk.h new file mode 100644 index 0000000000000000000000000000000000000000..92a89bee1b94caf1eb6a691904b5605e04feb0cd --- /dev/null +++ b/thirdParty/mavlink/include/pixhawk/pixhawk.h @@ -0,0 +1,80 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Thursday, March 31 2011, 22:06 UTC + */ +#ifndef PIXHAWK_H +#define PIXHAWK_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "../protocol.h" + +#define MAVLINK_ENABLED_PIXHAWK + + +#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 + +/** @brief Slugs parameter interface subsets */ +enum SLUGS_PID_INDX_IDS +{ + PID_YAW_DAMPER=2, + PID_PITCH=3, /* With comment: PID Pitch parameter*/ + PID_ALT_HOLD=50, + SLUGS_PID_INDX_IDS_ENUM_END +}; + +/** @brief Content Types for data transmission handshake */ +enum DATA_TYPES +{ + DATA_TYPE_JPEG_IMAGE=1, + DATA_TYPE_RAW_IMAGE=2, + DATA_TYPE_KINECT=3, + DATA_TYPES_ENUM_END +}; + + +// MESSAGE DEFINITIONS + +#include "./mavlink_msg_attitude_control.h" +#include "./mavlink_msg_set_cam_shutter.h" +#include "./mavlink_msg_image_triggered.h" +#include "./mavlink_msg_image_trigger_control.h" +#include "./mavlink_msg_image_available.h" +#include "./mavlink_msg_vision_position_estimate.h" +#include "./mavlink_msg_vicon_position_estimate.h" +#include "./mavlink_msg_position_control_setpoint_set.h" +#include "./mavlink_msg_position_control_offset_set.h" +#include "./mavlink_msg_position_control_setpoint.h" +#include "./mavlink_msg_marker.h" +#include "./mavlink_msg_raw_aux.h" +#include "./mavlink_msg_aux_status.h" +#include "./mavlink_msg_watchdog_heartbeat.h" +#include "./mavlink_msg_watchdog_process_info.h" +#include "./mavlink_msg_watchdog_process_status.h" +#include "./mavlink_msg_watchdog_command.h" +#include "./mavlink_msg_pattern_detected.h" +#include "./mavlink_msg_point_of_interest.h" +#include "./mavlink_msg_point_of_interest_connection.h" +#include "./mavlink_msg_data_transmission_handshake.h" +#include "./mavlink_msg_encapsulated_data.h" +#include "./mavlink_msg_brief_feature.h" +#ifdef __cplusplus +} +#endif +#endif diff --git a/thirdParty/mavlink/include/protocol.h b/thirdParty/mavlink/include/protocol.h new file mode 100644 index 0000000000000000000000000000000000000000..ed1f9546b499e2a1c3e10738102f70687e7cd3ae --- /dev/null +++ b/thirdParty/mavlink/include/protocol.h @@ -0,0 +1,982 @@ +#ifndef _MAVLINK_PROTOCOL_H_ +#define _MAVLINK_PROTOCOL_H_ + +#include "string.h" +#include "checksum.h" + +#include "mavlink_types.h" + + +/** + * @brief Initialize the communication stack + * + * This function has to be called before using commParseBuffer() to initialize the different status registers. + * + * @return Will initialize the different buffers and status registers. + */ +static void mavlink_parse_state_initialize(mavlink_status_t* initStatus) +{ + if ((initStatus->parse_state <= MAVLINK_PARSE_STATE_UNINIT) || (initStatus->parse_state > MAVLINK_PARSE_STATE_GOT_CRC1)) + { + initStatus->ck_a = 0; + initStatus->ck_b = 0; + initStatus->msg_received = 0; + initStatus->buffer_overrun = 0; + initStatus->parse_error = 0; + initStatus->parse_state = MAVLINK_PARSE_STATE_UNINIT; + initStatus->packet_idx = 0; + initStatus->packet_rx_drop_count = 0; + initStatus->packet_rx_success_count = 0; + initStatus->current_rx_seq = 0; + initStatus->current_tx_seq = 0; + } +} + +static inline mavlink_status_t* mavlink_get_channel_status(uint8_t chan) +{ + static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; + return &m_mavlink_status[chan]; +} + +/** + * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel + * + * This function calculates the checksum and sets length and aircraft id correctly. + * It assumes that the message id and the payload are already correctly set. + * + * @warning This function implicitely assumes the message is sent over channel zero. + * if the message is sent over a different channel it will reach the receiver + * without error, BUT the sequence number might be wrong due to the wrong + * channel sequence counter. This will result is wrongly reported excessive + * packet loss. Please use @see mavlink_{pack|encode}_headerless and then + * @see mavlink_finalize_message_chan before sending for a correct channel + * assignment. Please note that the mavlink_msg_xxx_pack and encode functions + * assign channel zero as default and thus induce possible loss counter errors.\ + * They have been left to ensure code compatibility. + * + * @see mavlink_finalize_message_chan + * @param msg Message to finalize + * @param system_id Id of the sending (this) system, 1-127 + * @param length Message length, usually just the counter incremented while packing the message + */ +static inline uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint16_t length) +{ + // This code part is the same for all messages; + uint16_t checksum; + msg->len = length; + msg->sysid = system_id; + 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; + 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 + + return length + MAVLINK_NUM_NON_STX_PAYLOAD_BYTES; +} + +/** + * @brief Finalize a MAVLink message with channel assignment + * + * This function calculates the checksum and sets length and aircraft id correctly. + * It assumes that the message id and the payload are already correctly set. This function + * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack + * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. + * + * @param msg Message to finalize + * @param system_id Id of the sending (this) system, 1-127 + * @param length Message length, usually just the counter incremented while packing the message + */ +static inline uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint16_t length) +{ + // This code part is the same for all messages; + uint16_t checksum; + msg->len = length; + msg->sysid = system_id; + msg->compid = component_id; + // One sequence number per component + msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; + mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->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 + + return length + MAVLINK_NUM_NON_STX_PAYLOAD_BYTES; +} + +/** + * @brief Pack a message to send it over a serial byte stream + */ +static inline uint16_t mavlink_msg_to_send_buffer(uint8_t* buffer, const mavlink_message_t* msg) +{ + *(buffer+0) = MAVLINK_STX; ///< Start transmit + memcpy((buffer+1), msg, msg->len + MAVLINK_CORE_HEADER_LEN); ///< Core header plus payload + *(buffer + msg->len + MAVLINK_CORE_HEADER_LEN + 1) = msg->ck_a; + *(buffer + msg->len + MAVLINK_CORE_HEADER_LEN + 2) = msg->ck_b; + return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; + return 0; +} + +/** + * @brief Get the required buffer size for this message + */ +static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) +{ + return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; +} + +union checksum_ { + uint16_t s; + uint8_t c[2]; +}; + +union __mavlink_bitfield { + uint8_t uint8; + int8_t int8; + uint16_t uint16; + int16_t int16; + uint32_t uint32; + int32_t int32; +}; + + +static inline void mavlink_start_checksum(mavlink_message_t* msg) +{ + union checksum_ ck; + crc_init(&(ck.s)); + msg->ck_a = ck.c[0]; + msg->ck_b = ck.c[1]; +} + +static inline void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) +{ + union checksum_ ck; + ck.c[0] = msg->ck_a; + ck.c[1] = msg->ck_b; + crc_accumulate(c, &(ck.s)); + msg->ck_a = ck.c[0]; + msg->ck_b = ck.c[1]; +} + +/** + * This is a convenience function which handles the complete MAVLink parsing. + * the function will parse one byte at a time and return the complete packet once + * it could be successfully decoded. Checksum and other failures will be silently + * ignored. + * + * @param chan ID of the current channel. This allows to parse different channels with this function. + * a channel is not a physical message channel like a serial port, but a logic partition of + * the communication streams in this case. COMM_NB is the limit for the number of channels + * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows + * @param c The char to barse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @return 0 if no message could be decoded, 1 else + * + * A typical use scenario of this function call is: + * + * @code + * #include // For fixed-width uint8_t type + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_parse_char(chan, byte, &msg)) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +static inline uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + 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)); + + mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message + mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status + int bufferIndex = 0; + + status->msg_received = 0; + + switch (status->parse_state) + { + case MAVLINK_PARSE_STATE_UNINIT: + case MAVLINK_PARSE_STATE_IDLE: + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + mavlink_start_checksum(rxmsg); + } + break; + + case MAVLINK_PARSE_STATE_GOT_STX: + if (status->msg_received) + { + status->buffer_overrun++; + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + } + else + { + // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 + rxmsg->len = c; + status->packet_idx = 0; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; + } + break; + + case MAVLINK_PARSE_STATE_GOT_LENGTH: + rxmsg->seq = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; + break; + + case MAVLINK_PARSE_STATE_GOT_SEQ: + rxmsg->sysid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; + break; + + case MAVLINK_PARSE_STATE_GOT_SYSID: + rxmsg->compid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; + break; + + case MAVLINK_PARSE_STATE_GOT_COMPID: + rxmsg->msgid = c; + mavlink_update_checksum(rxmsg, c); + if (rxmsg->len == 0) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + else + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; + } + break; + + case MAVLINK_PARSE_STATE_GOT_MSGID: + rxmsg->payload[status->packet_idx++] = c; + mavlink_update_checksum(rxmsg, c); + if (status->packet_idx == rxmsg->len) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + break; + + case MAVLINK_PARSE_STATE_GOT_PAYLOAD: + if (c != rxmsg->ck_a) + { + // Check first checksum byte + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + mavlink_start_checksum(rxmsg); + } + } + else + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; + } + break; + + case MAVLINK_PARSE_STATE_GOT_CRC1: + if (c != rxmsg->ck_b) + {// Check second checksum byte + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + mavlink_start_checksum(rxmsg); + } + } + else + { + // Successfully got message + status->msg_received = 1; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); + } + break; + } + + bufferIndex++; + // If a message has been sucessfully decoded, check index + if (status->msg_received == 1) + { + //while(status->current_seq != rxmsg->seq) + //{ + // status->packet_rx_drop_count++; + // status->current_seq++; + //} + status->current_rx_seq = rxmsg->seq; + // Initial condition: If no packet has been received so far, drop count is undefined + if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; + // Count this packet as received + status->packet_rx_success_count++; + } + + r_mavlink_status->current_rx_seq = status->current_rx_seq+1; + r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; + r_mavlink_status->packet_rx_drop_count = status->parse_error; + status->parse_error = 0; + return status->msg_received; +} + + +/** + * This is a convenience function which handles the complete MAVLink parsing. + * the function will parse one byte at a time and return the complete packet once + * it could be successfully decoded. Checksum and other failures will be silently + * ignored. + * + * @param chan ID of the current channel. This allows to parse different channels with this function. + * a channel is not a physical message channel like a serial port, but a logic partition of + * the communication streams in this case. COMM_NB is the limit for the number of channels + * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows + * @param c The char to barse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @return 0 if no message could be decoded, 1 else + * + * A typical use scenario of this function call is: + * + * @code + * #include // For fixed-width uint8_t type + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_parse_char(chan, byte, &msg)) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ + +#define MAVLINK_PACKET_START_CANDIDATES 50 +/* +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) +{ + 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) + { + m_packet_start[chan][++(m_packet_start_index_write[chan]) % MAVLINK_PACKET_START_CANDIDATES] = m_msgbuf_index[chan]; + } + + // Parse normally, if a CRC mismatch occurs retry with the next packet index +} +// 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]); +// +//mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message +//mavlink_status_t* status = &m_mavlink_status[chan]; ///< The current decode status +//int bufferIndex = 0; +// +//status->msg_received = 0; +// +//switch (status->parse_state) +//{ +//case MAVLINK_PARSE_STATE_UNINIT: +//case MAVLINK_PARSE_STATE_IDLE: +// if (c == MAVLINK_STX) +// { +// status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; +// mavlink_start_checksum(rxmsg); +// } +// break; +// +//case MAVLINK_PARSE_STATE_GOT_STX: +// if (status->msg_received) +// { +// status->buffer_overrun++; +// status->parse_error++; +// status->msg_received = 0; +// status->parse_state = MAVLINK_PARSE_STATE_IDLE; +// } +// else +// { +// // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 +// rxmsg->len = c; +// status->packet_idx = 0; +// mavlink_update_checksum(rxmsg, c); +// status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; +// } +// break; +// +//case MAVLINK_PARSE_STATE_GOT_LENGTH: +// rxmsg->seq = c; +// mavlink_update_checksum(rxmsg, c); +// status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; +// break; +// +//case MAVLINK_PARSE_STATE_GOT_SEQ: +// rxmsg->sysid = c; +// mavlink_update_checksum(rxmsg, c); +// status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; +// break; +// +//case MAVLINK_PARSE_STATE_GOT_SYSID: +// rxmsg->compid = c; +// mavlink_update_checksum(rxmsg, c); +// status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; +// break; +// +//case MAVLINK_PARSE_STATE_GOT_COMPID: +// rxmsg->msgid = c; +// mavlink_update_checksum(rxmsg, c); +// if (rxmsg->len == 0) +// { +// status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; +// } +// else +// { +// status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; +// } +// break; +// +//case MAVLINK_PARSE_STATE_GOT_MSGID: +// rxmsg->payload[status->packet_idx++] = c; +// mavlink_update_checksum(rxmsg, c); +// if (status->packet_idx == rxmsg->len) +// { +// status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; +// } +// break; +// +//case MAVLINK_PARSE_STATE_GOT_PAYLOAD: +// if (c != rxmsg->ck_a) +// { +// // Check first checksum byte +// status->parse_error++; +// status->msg_received = 0; +// status->parse_state = MAVLINK_PARSE_STATE_IDLE; +// } +// else +// { +// status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; +// } +// break; +// +//case MAVLINK_PARSE_STATE_GOT_CRC1: +// if (c != rxmsg->ck_b) +// {// Check second checksum byte +// status->parse_error++; +// status->msg_received = 0; +// status->parse_state = MAVLINK_PARSE_STATE_IDLE; +// } +// else +// { +// // Successfully got message +// status->msg_received = 1; +// status->parse_state = MAVLINK_PARSE_STATE_IDLE; +// memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); +// } +// break; +//} + +bufferIndex++; +// If a message has been sucessfully decoded, check index +if (status->msg_received == 1) +{ + //while(status->current_seq != rxmsg->seq) + //{ + // status->packet_rx_drop_count++; + // status->current_seq++; + //} + status->current_seq = rxmsg->seq; + // Initial condition: If no packet has been received so far, drop count is undefined + if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; + // Count this packet as received + status->packet_rx_success_count++; +} + +r_mavlink_status->current_seq = status->current_seq+1; +r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; +r_mavlink_status->packet_rx_drop_count = status->parse_error; +return status->msg_received; +} + */ + + +typedef union __generic_16bit +{ + uint8_t b[2]; + int16_t s; +} generic_16bit; + +typedef union __generic_32bit +{ + uint8_t b[4]; + float f; + int32_t i; + int16_t s; +} generic_32bit; + +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; + +/** + * @brief Place an unsigned byte into the buffer + * + * @param b the byte to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_uint8_t_by_index(uint8_t b, uint8_t bindex, uint8_t* buffer) +{ + *(buffer + bindex) = b; + return sizeof(b); +} + +/** + * @brief Place a signed byte into the buffer + * + * @param b the byte to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_int8_t_by_index(int8_t b, int8_t bindex, uint8_t* buffer) +{ + *(buffer + bindex) = (uint8_t)b; + return sizeof(b); +} + +/** + * @brief Place two unsigned bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_uint16_t_by_index(uint16_t b, const uint8_t bindex, uint8_t* buffer) +{ + buffer[bindex] = (b>>8)&0xff; + buffer[bindex+1] = (b & 0xff); + return sizeof(b); +} + +/** + * @brief Place two signed bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_int16_t_by_index(int16_t b, uint8_t bindex, uint8_t* buffer) +{ + return put_uint16_t_by_index(b, bindex, buffer); +} + +/** + * @brief Place four unsigned bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_uint32_t_by_index(uint32_t b, const uint8_t bindex, uint8_t* buffer) +{ + buffer[bindex] = (b>>24)&0xff; + buffer[bindex+1] = (b>>16)&0xff; + buffer[bindex+2] = (b>>8)&0xff; + buffer[bindex+3] = (b & 0xff); + return sizeof(b); +} + +/** + * @brief Place four signed bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_int32_t_by_index(int32_t b, uint8_t bindex, uint8_t* buffer) +{ + buffer[bindex] = (b>>24)&0xff; + buffer[bindex+1] = (b>>16)&0xff; + buffer[bindex+2] = (b>>8)&0xff; + buffer[bindex+3] = (b & 0xff); + return sizeof(b); +} + +/** + * @brief Place four unsigned bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_uint64_t_by_index(uint64_t b, const uint8_t bindex, uint8_t* buffer) +{ + buffer[bindex] = (b>>56)&0xff; + buffer[bindex+1] = (b>>48)&0xff; + buffer[bindex+2] = (b>>40)&0xff; + buffer[bindex+3] = (b>>32)&0xff; + buffer[bindex+4] = (b>>24)&0xff; + buffer[bindex+5] = (b>>16)&0xff; + buffer[bindex+6] = (b>>8)&0xff; + buffer[bindex+7] = (b & 0xff); + return sizeof(b); +} + +/** + * @brief Place four signed bytes into the buffer + * + * @param b the bytes to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_int64_t_by_index(int64_t b, uint8_t bindex, uint8_t* buffer) +{ + return put_uint64_t_by_index(b, bindex, buffer); +} + +/** + * @brief Place a float into the buffer + * + * @param b the float to add + * @param bindex the position in the packet + * @param buffer the packet buffer + * @return the new position of the last used byte in the buffer + */ +static inline uint8_t put_float_by_index(float b, uint8_t bindex, uint8_t* buffer) +{ + generic_32bit g; + g.f = b; + return put_int32_t_by_index(g.i, bindex, buffer); +} + +/** + * @brief Place an array into the buffer + * + * @param b the array to add + * @param length size of the array (for strings: length WITH '\0' char) + * @param bindex the position in the packet + * @param buffer packet buffer + * @return new position of the last used byte in the buffer + */ +static inline uint8_t put_array_by_index(const int8_t* b, uint8_t length, uint8_t bindex, uint8_t* buffer) +{ + memcpy(buffer+bindex, b, length); + return length; +} + +/** + * @brief Place a string into the buffer + * + * @param b the string to add + * @param maxlength size of the array (for strings: length WITHOUT '\0' char) + * @param bindex the position in the packet + * @param buffer packet buffer + * @return new position of the last used byte in the buffer + */ +static inline uint8_t put_string_by_index(const char* b, uint8_t maxlength, uint8_t bindex, uint8_t* buffer) +{ + uint16_t length = 0; + // Copy string into buffer, ensuring not to exceed the buffer size + int i; + for (i = 1; i < maxlength; i++) + { + length++; + // String characters + if (i < (maxlength - 1)) + { + buffer[bindex+i] = b[i]; + // Stop at null character + if (b[i] == '\0') + { + break; + } + } + // Enforce null termination at end of buffer + else if (i == (maxlength - 1)) + { + buffer[i] = '\0'; + } + } + // Write length into first field + put_uint8_t_by_index(length, bindex, buffer); + return length; +} + +/** + * @brief Put a bitfield of length 1-32 bit into the buffer + * + * @param b the value to add, will be encoded in the bitfield + * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. + * @param packet_index the position in the packet (the index of the first byte to use) + * @param bit_index the position in the byte (the index of the first bit to use) + * @param buffer packet buffer to write into + * @return new position of the last used byte in the buffer + */ +static inline uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) +{ + uint16_t bits_remain = bits; + // Transform number into network order + generic_32bit bin; + generic_32bit bout; + uint8_t i_bit_index, i_byte_index, curr_bits_n; + bin.i = b; + bout.b[0] = bin.b[3]; + bout.b[1] = bin.b[2]; + bout.b[2] = bin.b[1]; + bout.b[3] = bin.b[0]; + + // buffer in + // 01100000 01000000 00000000 11110001 + // buffer out + // 11110001 00000000 01000000 01100000 + + // Existing partly filled byte (four free slots) + // 0111xxxx + + // Mask n free bits + // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 + // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 + + // Shift n bits into the right position + // out = in >> n; + + // Mask and shift bytes + i_bit_index = bit_index; + i_byte_index = packet_index; + if (bit_index > 0) + { + // If bits were available at start, they were available + // in the byte before the current index + i_byte_index--; + } + + // While bits have not been packed yet + while (bits_remain > 0) + { + // Bits still have to be packed + // there can be more than 8 bits, so + // we might have to pack them into more than one byte + + // First pack everything we can into the current 'open' byte + //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 + //FIXME + if (bits_remain <= (8 - i_bit_index)) + { + // Enough space + curr_bits_n = bits_remain; + } + else + { + curr_bits_n = (8 - i_bit_index); + } + + // Pack these n bits into the current byte + // Mask out whatever was at that position with ones (xxx11111) + buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); + // Put content to this position, by masking out the non-used part + buffer[i_byte_index] |= ((0x00 << curr_bits_n) & bout.i); + + // Increment the bit index + i_bit_index += curr_bits_n; + + // Now proceed to the next byte, if necessary + bits_remain -= curr_bits_n; + if (bits_remain > 0) + { + // Offer another 8 bits / one byte + i_byte_index++; + i_bit_index = 0; + } + } + + *r_bit_index = i_bit_index; + // If a partly filled byte is present, mark this as consumed + if (i_bit_index != 7) i_byte_index++; + return i_byte_index - packet_index; +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +// To make MAVLink work on your MCU, define a similar function + +/* + +#include "mavlink_types.h" + +void comm_send_ch(mavlink_channel_t chan, uint8_t ch) +{ + if (chan == MAVLINK_COMM_0) + { + uart0_transmit(ch); + } + if (chan == MAVLINK_COMM_1) + { + uart1_transmit(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) +{ + // ARM7 MCU board implementation + // Create pointer on message struct + // Send STX + comm_send_ch(chan, MAVLINK_STX); + comm_send_ch(chan, msg->len); + comm_send_ch(chan, msg->seq); + comm_send_ch(chan, msg->sysid); + comm_send_ch(chan, msg->compid); + comm_send_ch(chan, msg->msgid); + for(uint16_t i = 0; i < msg->len; i++) + { + comm_send_ch(chan, msg->payload[i]); + } + comm_send_ch(chan, msg->ck_a); + comm_send_ch(chan, msg->ck_b); +} +#endif + +#endif /* _MAVLINK_PROTOCOL_H_ */ diff --git a/thirdParty/mavlink/include/slugs/mavlink.h b/thirdParty/mavlink/include/slugs/mavlink.h new file mode 100644 index 0000000000000000000000000000000000000000..2a1fb06684bbc14eb75745ec146085305dda21ac --- /dev/null +++ b/thirdParty/mavlink/include/slugs/mavlink.h @@ -0,0 +1,11 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Thursday, March 31 2011, 22:06 UTC + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#include "slugs.h" + +#endif diff --git a/thirdParty/mavlink/include/slugs/mavlink_msg_air_data.h b/thirdParty/mavlink/include/slugs/mavlink_msg_air_data.h new file mode 100644 index 0000000000000000000000000000000000000000..2b212ae1ba0d55d913204ec9fea1ba0f75920701 --- /dev/null +++ b/thirdParty/mavlink/include/slugs/mavlink_msg_air_data.h @@ -0,0 +1,148 @@ +// MESSAGE AIR_DATA PACKING + +#define MAVLINK_MSG_ID_AIR_DATA 171 + +typedef struct __mavlink_air_data_t +{ + float dynamicPressure; ///< Dynamic pressure (Pa) + float staticPressure; ///< Static pressure (Pa) + uint16_t temperature; ///< Board temperature + +} mavlink_air_data_t; + + + +/** + * @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) + * @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(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float dynamicPressure, float staticPressure, uint16_t temperature) +{ + 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 + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @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_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, dynamicPressure, staticPressure, temperature); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE AIR_DATA UNPACKING + +/** + * @brief Get field dynamicPressure from air_data message + * + * @return Dynamic pressure (Pa) + */ +static inline float mavlink_msg_air_data_get_dynamicPressure(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 staticPressure from air_data message + * + * @return Static pressure (Pa) + */ +static inline float mavlink_msg_air_data_get_staticPressure(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 temperature from air_data message + * + * @return Board temperature + */ +static inline uint16_t mavlink_msg_air_data_get_temperature(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[0]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[1]; + 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); + air_data->staticPressure = mavlink_msg_air_data_get_staticPressure(msg); + air_data->temperature = mavlink_msg_air_data_get_temperature(msg); +} diff --git a/thirdParty/mavlink/include/slugs/mavlink_msg_cpu_load.h b/thirdParty/mavlink/include/slugs/mavlink_msg_cpu_load.h new file mode 100644 index 0000000000000000000000000000000000000000..265aa3fceeacaa25645b0196e7a078ff7ea38d6b --- /dev/null +++ b/thirdParty/mavlink/include/slugs/mavlink_msg_cpu_load.h @@ -0,0 +1,138 @@ +// MESSAGE CPU_LOAD PACKING + +#define MAVLINK_MSG_ID_CPU_LOAD 170 + +typedef struct __mavlink_cpu_load_t +{ + uint8_t sensLoad; ///< Sensor DSC Load + uint8_t ctrlLoad; ///< Control DSC Load + uint16_t batVolt; ///< Battery Voltage in millivolts + +} mavlink_cpu_load_t; + + + +/** + * @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 + * @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(uint8_t system_id, uint8_t component_id, 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(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); +} + +/** + * @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(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, sensLoad, ctrlLoad, batVolt); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE CPU_LOAD UNPACKING + +/** + * @brief Get field sensLoad from cpu_load message + * + * @return Sensor DSC Load + */ +static inline uint8_t mavlink_msg_cpu_load_get_sensLoad(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field ctrlLoad from cpu_load message + * + * @return Control DSC Load + */ +static inline uint8_t mavlink_msg_cpu_load_get_ctrlLoad(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field batVolt from cpu_load message + * + * @return Battery Voltage in millivolts + */ +static inline uint16_t mavlink_msg_cpu_load_get_batVolt(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 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); + cpu_load->ctrlLoad = mavlink_msg_cpu_load_get_ctrlLoad(msg); + cpu_load->batVolt = mavlink_msg_cpu_load_get_batVolt(msg); +} diff --git a/thirdParty/mavlink/include/slugs/mavlink_msg_ctrl_srfc_pt.h b/thirdParty/mavlink/include/slugs/mavlink_msg_ctrl_srfc_pt.h new file mode 100644 index 0000000000000000000000000000000000000000..9221dc4f00d1032d7b9b05a30501fbc5a716a7d3 --- /dev/null +++ b/thirdParty/mavlink/include/slugs/mavlink_msg_ctrl_srfc_pt.h @@ -0,0 +1,121 @@ +// MESSAGE CTRL_SRFC_PT PACKING + +#define MAVLINK_MSG_ID_CTRL_SRFC_PT 181 + +typedef struct __mavlink_ctrl_srfc_pt_t +{ + uint8_t target; ///< The system setting the commands + uint16_t bitfieldPt; ///< Bitfield containing the PT configuration + +} mavlink_ctrl_srfc_pt_t; + + + +/** + * @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 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack(uint8_t system_id, uint8_t component_id, 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(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_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, bitfieldPt); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE CTRL_SRFC_PT UNPACKING + +/** + * @brief Get field target from ctrl_srfc_pt message + * + * @return The system setting the commands + */ +static inline uint8_t mavlink_msg_ctrl_srfc_pt_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field bitfieldPt from ctrl_srfc_pt message + * + * @return Bitfield containing the PT configuration + */ +static inline uint16_t mavlink_msg_ctrl_srfc_pt_get_bitfieldPt(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint8_t))[0]; + r.b[0] = (msg->payload+sizeof(uint8_t))[1]; + 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); + ctrl_srfc_pt->bitfieldPt = mavlink_msg_ctrl_srfc_pt_get_bitfieldPt(msg); +} diff --git a/thirdParty/mavlink/include/slugs/mavlink_msg_data_log.h b/thirdParty/mavlink/include/slugs/mavlink_msg_data_log.h new file mode 100644 index 0000000000000000000000000000000000000000..cbcc0daba3804ba35822e4bc6f2b429cdeaba783 --- /dev/null +++ b/thirdParty/mavlink/include/slugs/mavlink_msg_data_log.h @@ -0,0 +1,216 @@ +// MESSAGE DATA_LOG PACKING + +#define MAVLINK_MSG_ID_DATA_LOG 177 + +typedef struct __mavlink_data_log_t +{ + float fl_1; ///< Log value 1 + float fl_2; ///< Log value 2 + float fl_3; ///< Log value 3 + float fl_4; ///< Log value 4 + float fl_5; ///< Log value 5 + float fl_6; ///< Log value 6 + +} mavlink_data_log_t; + + + +/** + * @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 + * @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(uint8_t system_id, uint8_t component_id, 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(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_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); +} + +#endif +// MESSAGE DATA_LOG UNPACKING + +/** + * @brief Get field fl_1 from data_log message + * + * @return Log value 1 + */ +static inline float mavlink_msg_data_log_get_fl_1(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 fl_2 from data_log message + * + * @return Log value 2 + */ +static inline float mavlink_msg_data_log_get_fl_2(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 fl_3 from data_log message + * + * @return Log value 3 + */ +static inline float mavlink_msg_data_log_get_fl_3(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 fl_4 from data_log message + * + * @return Log value 4 + */ +static inline float mavlink_msg_data_log_get_fl_4(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 fl_5 from data_log message + * + * @return Log value 5 + */ +static inline float mavlink_msg_data_log_get_fl_5(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 fl_6 from data_log message + * + * @return Log value 6 + */ +static inline float mavlink_msg_data_log_get_fl_6(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 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); + data_log->fl_2 = mavlink_msg_data_log_get_fl_2(msg); + data_log->fl_3 = mavlink_msg_data_log_get_fl_3(msg); + data_log->fl_4 = mavlink_msg_data_log_get_fl_4(msg); + data_log->fl_5 = mavlink_msg_data_log_get_fl_5(msg); + data_log->fl_6 = mavlink_msg_data_log_get_fl_6(msg); +} diff --git a/thirdParty/mavlink/include/slugs/mavlink_msg_diagnostic.h b/thirdParty/mavlink/include/slugs/mavlink_msg_diagnostic.h new file mode 100644 index 0000000000000000000000000000000000000000..f3798f59bb869b8c74a4611507c8abcffb2c13db --- /dev/null +++ b/thirdParty/mavlink/include/slugs/mavlink_msg_diagnostic.h @@ -0,0 +1,210 @@ +// MESSAGE DIAGNOSTIC PACKING + +#define MAVLINK_MSG_ID_DIAGNOSTIC 173 + +typedef struct __mavlink_diagnostic_t +{ + float diagFl1; ///< Diagnostic float 1 + float diagFl2; ///< Diagnostic float 2 + float diagFl3; ///< Diagnostic float 3 + int16_t diagSh1; ///< Diagnostic short 1 + int16_t diagSh2; ///< Diagnostic short 2 + int16_t diagSh3; ///< Diagnostic short 3 + +} mavlink_diagnostic_t; + + + +/** + * @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 + * @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(uint8_t system_id, uint8_t component_id, 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_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); +} + +/** + * @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_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, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE DIAGNOSTIC UNPACKING + +/** + * @brief Get field diagFl1 from diagnostic message + * + * @return Diagnostic float 1 + */ +static inline float mavlink_msg_diagnostic_get_diagFl1(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 diagFl2 from diagnostic message + * + * @return Diagnostic float 2 + */ +static inline float mavlink_msg_diagnostic_get_diagFl2(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 diagFl3 from diagnostic message + * + * @return Diagnostic float 3 + */ +static inline float mavlink_msg_diagnostic_get_diagFl3(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 diagSh1 from diagnostic message + * + * @return Diagnostic short 1 + */ +static inline int16_t mavlink_msg_diagnostic_get_diagSh1(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field diagSh2 from diagnostic message + * + * @return Diagnostic short 2 + */ +static inline int16_t mavlink_msg_diagnostic_get_diagSh2(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t))[1]; + return (int16_t)r.s; +} + +/** + * @brief Get field diagSh3 from diagnostic message + * + * @return Diagnostic short 3 + */ +static inline int16_t mavlink_msg_diagnostic_get_diagSh3(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[1]; + 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); + diagnostic->diagFl2 = mavlink_msg_diagnostic_get_diagFl2(msg); + diagnostic->diagFl3 = mavlink_msg_diagnostic_get_diagFl3(msg); + diagnostic->diagSh1 = mavlink_msg_diagnostic_get_diagSh1(msg); + diagnostic->diagSh2 = mavlink_msg_diagnostic_get_diagSh2(msg); + diagnostic->diagSh3 = mavlink_msg_diagnostic_get_diagSh3(msg); +} diff --git a/thirdParty/mavlink/include/slugs/mavlink_msg_gps_date_time.h b/thirdParty/mavlink/include/slugs/mavlink_msg_gps_date_time.h new file mode 100644 index 0000000000000000000000000000000000000000..199cbb9ec264f0e8a15920aedb42fdcd373763d5 --- /dev/null +++ b/thirdParty/mavlink/include/slugs/mavlink_msg_gps_date_time.h @@ -0,0 +1,203 @@ +// MESSAGE GPS_DATE_TIME PACKING + +#define MAVLINK_MSG_ID_GPS_DATE_TIME 179 + +typedef struct __mavlink_gps_date_time_t +{ + uint8_t year; ///< Year reported by Gps + uint8_t month; ///< Month reported by Gps + uint8_t day; ///< Day reported by Gps + uint8_t hour; ///< Hour reported by Gps + uint8_t min; ///< Min reported by Gps + uint8_t sec; ///< Sec reported by Gps + uint8_t visSat; ///< Visible sattelites reported by Gps + +} mavlink_gps_date_time_t; + + + +/** + * @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 + * @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(uint8_t system_id, uint8_t component_id, 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(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_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, year, month, day, hour, min, sec, visSat); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE GPS_DATE_TIME UNPACKING + +/** + * @brief Get field year from gps_date_time message + * + * @return Year reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_year(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field month from gps_date_time message + * + * @return Month reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_month(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field day from gps_date_time message + * + * @return Day reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_day(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field hour from gps_date_time message + * + * @return Hour reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_hour(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field min from gps_date_time message + * + * @return Min reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_min(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field sec from gps_date_time message + * + * @return Sec reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_sec(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field visSat from gps_date_time message + * + * @return Visible sattelites reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_visSat(const mavlink_message_t* msg) +{ + 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); + gps_date_time->month = mavlink_msg_gps_date_time_get_month(msg); + gps_date_time->day = mavlink_msg_gps_date_time_get_day(msg); + gps_date_time->hour = mavlink_msg_gps_date_time_get_hour(msg); + gps_date_time->min = mavlink_msg_gps_date_time_get_min(msg); + gps_date_time->sec = mavlink_msg_gps_date_time_get_sec(msg); + gps_date_time->visSat = mavlink_msg_gps_date_time_get_visSat(msg); +} diff --git a/thirdParty/mavlink/include/slugs/mavlink_msg_mid_lvl_cmds.h b/thirdParty/mavlink/include/slugs/mavlink_msg_mid_lvl_cmds.h new file mode 100644 index 0000000000000000000000000000000000000000..a0d78b1ceb9e627377ed4af66808d0c8838172dd --- /dev/null +++ b/thirdParty/mavlink/include/slugs/mavlink_msg_mid_lvl_cmds.h @@ -0,0 +1,167 @@ +// MESSAGE MID_LVL_CMDS PACKING + +#define MAVLINK_MSG_ID_MID_LVL_CMDS 180 + +typedef struct __mavlink_mid_lvl_cmds_t +{ + uint8_t target; ///< The system setting the commands + float hCommand; ///< Commanded Airspeed + float uCommand; ///< Log value 2 + float rCommand; ///< Log value 3 + +} mavlink_mid_lvl_cmds_t; + + + +/** + * @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 + * @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(uint8_t system_id, uint8_t component_id, 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(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_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, hCommand, uCommand, rCommand); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE MID_LVL_CMDS UNPACKING + +/** + * @brief Get field target from mid_lvl_cmds message + * + * @return The system setting the commands + */ +static inline uint8_t mavlink_msg_mid_lvl_cmds_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field hCommand from mid_lvl_cmds message + * + * @return Commanded Airspeed + */ +static inline float mavlink_msg_mid_lvl_cmds_get_hCommand(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 uCommand from mid_lvl_cmds message + * + * @return Log value 2 + */ +static inline float mavlink_msg_mid_lvl_cmds_get_uCommand(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 rCommand from mid_lvl_cmds message + * + * @return Log value 3 + */ +static inline float mavlink_msg_mid_lvl_cmds_get_rCommand(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 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); + mid_lvl_cmds->hCommand = mavlink_msg_mid_lvl_cmds_get_hCommand(msg); + mid_lvl_cmds->uCommand = mavlink_msg_mid_lvl_cmds_get_uCommand(msg); + mid_lvl_cmds->rCommand = mavlink_msg_mid_lvl_cmds_get_rCommand(msg); +} diff --git a/thirdParty/mavlink/include/slugs/mavlink_msg_sensor_bias.h b/thirdParty/mavlink/include/slugs/mavlink_msg_sensor_bias.h new file mode 100644 index 0000000000000000000000000000000000000000..8b40bdd67a774b6275904f2e4897370f2e69fb33 --- /dev/null +++ b/thirdParty/mavlink/include/slugs/mavlink_msg_sensor_bias.h @@ -0,0 +1,216 @@ +// MESSAGE SENSOR_BIAS PACKING + +#define MAVLINK_MSG_ID_SENSOR_BIAS 172 + +typedef struct __mavlink_sensor_bias_t +{ + float axBias; ///< Accelerometer X bias (m/s) + float ayBias; ///< Accelerometer Y bias (m/s) + float azBias; ///< Accelerometer Z bias (m/s) + float gxBias; ///< Gyro X bias (rad/s) + float gyBias; ///< Gyro Y bias (rad/s) + float gzBias; ///< Gyro Z bias (rad/s) + +} mavlink_sensor_bias_t; + + + +/** + * @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) + * @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(uint8_t system_id, uint8_t component_id, 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_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); +} + +/** + * @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_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, axBias, ayBias, azBias, gxBias, gyBias, gzBias); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SENSOR_BIAS UNPACKING + +/** + * @brief Get field axBias from sensor_bias message + * + * @return Accelerometer X bias (m/s) + */ +static inline float mavlink_msg_sensor_bias_get_axBias(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 ayBias from sensor_bias message + * + * @return Accelerometer Y bias (m/s) + */ +static inline float mavlink_msg_sensor_bias_get_ayBias(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 azBias from sensor_bias message + * + * @return Accelerometer Z bias (m/s) + */ +static inline float mavlink_msg_sensor_bias_get_azBias(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 gxBias from sensor_bias message + * + * @return Gyro X bias (rad/s) + */ +static inline float mavlink_msg_sensor_bias_get_gxBias(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 gyBias from sensor_bias message + * + * @return Gyro Y bias (rad/s) + */ +static inline float mavlink_msg_sensor_bias_get_gyBias(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 gzBias from sensor_bias message + * + * @return Gyro Z bias (rad/s) + */ +static inline float mavlink_msg_sensor_bias_get_gzBias(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 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); + sensor_bias->ayBias = mavlink_msg_sensor_bias_get_ayBias(msg); + sensor_bias->azBias = mavlink_msg_sensor_bias_get_azBias(msg); + sensor_bias->gxBias = mavlink_msg_sensor_bias_get_gxBias(msg); + sensor_bias->gyBias = mavlink_msg_sensor_bias_get_gyBias(msg); + sensor_bias->gzBias = mavlink_msg_sensor_bias_get_gzBias(msg); +} diff --git a/thirdParty/mavlink/include/slugs/mavlink_msg_slugs_action.h b/thirdParty/mavlink/include/slugs/mavlink_msg_slugs_action.h new file mode 100644 index 0000000000000000000000000000000000000000..0664166567d84db5b432fcb1e852bb3207ba47c3 --- /dev/null +++ b/thirdParty/mavlink/include/slugs/mavlink_msg_slugs_action.h @@ -0,0 +1,138 @@ +// MESSAGE SLUGS_ACTION PACKING + +#define MAVLINK_MSG_ID_SLUGS_ACTION 183 + +typedef struct __mavlink_slugs_action_t +{ + uint8_t target; ///< The system reporting the action + uint8_t actionId; ///< Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + uint16_t actionVal; ///< Value associated with the action + +} mavlink_slugs_action_t; + + + +/** + * @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 + * @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(uint8_t system_id, uint8_t component_id, 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(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_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, actionId, actionVal); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SLUGS_ACTION UNPACKING + +/** + * @brief Get field target from slugs_action message + * + * @return The system reporting the action + */ +static inline uint8_t mavlink_msg_slugs_action_get_target(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Get field actionId from slugs_action message + * + * @return Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + */ +static inline uint8_t mavlink_msg_slugs_action_get_actionId(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; +} + +/** + * @brief Get field actionVal from slugs_action message + * + * @return Value associated with the action + */ +static inline uint16_t mavlink_msg_slugs_action_get_actionVal(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 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); + slugs_action->actionId = mavlink_msg_slugs_action_get_actionId(msg); + slugs_action->actionVal = mavlink_msg_slugs_action_get_actionVal(msg); +} diff --git a/thirdParty/mavlink/include/slugs/mavlink_msg_slugs_navigation.h b/thirdParty/mavlink/include/slugs/mavlink_msg_slugs_navigation.h new file mode 100644 index 0000000000000000000000000000000000000000..f1a54cb3e4408d52ec2531e22429cb567bc95a7c --- /dev/null +++ b/thirdParty/mavlink/include/slugs/mavlink_msg_slugs_navigation.h @@ -0,0 +1,272 @@ +// MESSAGE SLUGS_NAVIGATION PACKING + +#define MAVLINK_MSG_ID_SLUGS_NAVIGATION 176 + +typedef struct __mavlink_slugs_navigation_t +{ + float u_m; ///< Measured Airspeed prior to the Nav Filter + float phi_c; ///< Commanded Roll + float theta_c; ///< Commanded Pitch + float psiDot_c; ///< Commanded Turn rate + float ay_body; ///< Y component of the body acceleration + float totalDist; ///< Total Distance to Run on this leg of Navigation + float dist2Go; ///< Remaining distance to Run on this leg of Navigation + uint8_t fromWP; ///< Origin WP + uint8_t toWP; ///< Destination WP + +} mavlink_slugs_navigation_t; + + + +/** + * @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 + * @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(uint8_t system_id, uint8_t component_id, 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(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_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); +} + +#endif +// MESSAGE SLUGS_NAVIGATION UNPACKING + +/** + * @brief Get field u_m from slugs_navigation message + * + * @return Measured Airspeed prior to the Nav Filter + */ +static inline float mavlink_msg_slugs_navigation_get_u_m(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 phi_c from slugs_navigation message + * + * @return Commanded Roll + */ +static inline float mavlink_msg_slugs_navigation_get_phi_c(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 theta_c from slugs_navigation message + * + * @return Commanded Pitch + */ +static inline float mavlink_msg_slugs_navigation_get_theta_c(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 psiDot_c from slugs_navigation message + * + * @return Commanded Turn rate + */ +static inline float mavlink_msg_slugs_navigation_get_psiDot_c(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 ay_body from slugs_navigation message + * + * @return Y component of the body acceleration + */ +static inline float mavlink_msg_slugs_navigation_get_ay_body(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 totalDist from slugs_navigation message + * + * @return Total Distance to Run on this leg of Navigation + */ +static inline float mavlink_msg_slugs_navigation_get_totalDist(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 dist2Go from slugs_navigation message + * + * @return Remaining distance to Run on this leg of Navigation + */ +static inline float mavlink_msg_slugs_navigation_get_dist2Go(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 fromWP from slugs_navigation message + * + * @return Origin WP + */ +static inline uint8_t mavlink_msg_slugs_navigation_get_fromWP(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; +} + +/** + * @brief Get field toWP from slugs_navigation message + * + * @return Destination WP + */ +static inline uint8_t mavlink_msg_slugs_navigation_get_toWP(const mavlink_message_t* msg) +{ + 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); + slugs_navigation->phi_c = mavlink_msg_slugs_navigation_get_phi_c(msg); + slugs_navigation->theta_c = mavlink_msg_slugs_navigation_get_theta_c(msg); + slugs_navigation->psiDot_c = mavlink_msg_slugs_navigation_get_psiDot_c(msg); + slugs_navigation->ay_body = mavlink_msg_slugs_navigation_get_ay_body(msg); + slugs_navigation->totalDist = mavlink_msg_slugs_navigation_get_totalDist(msg); + slugs_navigation->dist2Go = mavlink_msg_slugs_navigation_get_dist2Go(msg); + slugs_navigation->fromWP = mavlink_msg_slugs_navigation_get_fromWP(msg); + slugs_navigation->toWP = mavlink_msg_slugs_navigation_get_toWP(msg); +} diff --git a/thirdParty/mavlink/include/slugs/slugs.h b/thirdParty/mavlink/include/slugs/slugs.h new file mode 100644 index 0000000000000000000000000000000000000000..fe792c6800ebb1824a504fa0b516f423e3c27112 --- /dev/null +++ b/thirdParty/mavlink/include/slugs/slugs.h @@ -0,0 +1,49 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Thursday, March 31 2011, 22:06 UTC + */ +#ifndef SLUGS_H +#define SLUGS_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "../protocol.h" + +#define MAVLINK_ENABLED_SLUGS + + +#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 + + +// MESSAGE DEFINITIONS + +#include "./mavlink_msg_cpu_load.h" +#include "./mavlink_msg_air_data.h" +#include "./mavlink_msg_sensor_bias.h" +#include "./mavlink_msg_diagnostic.h" +#include "./mavlink_msg_slugs_navigation.h" +#include "./mavlink_msg_data_log.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_slugs_action.h" +#ifdef __cplusplus +} +#endif +#endif diff --git a/thirdParty/mavlink/include/ualberta/mavlink.h b/thirdParty/mavlink/include/ualberta/mavlink.h new file mode 100644 index 0000000000000000000000000000000000000000..8d850dff6eb9cf029cb3bafbd2014f5ee82b1df4 --- /dev/null +++ b/thirdParty/mavlink/include/ualberta/mavlink.h @@ -0,0 +1,11 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Thursday, March 31 2011, 22:06 UTC + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#include "ualberta.h" + +#endif diff --git a/thirdParty/mavlink/include/ualberta/mavlink_msg_nav_filter_bias.h b/thirdParty/mavlink/include/ualberta/mavlink_msg_nav_filter_bias.h new file mode 100644 index 0000000000000000000000000000000000000000..a011fc1ab4f6f7b8587f8482cef6d0f3599c80a1 --- /dev/null +++ b/thirdParty/mavlink/include/ualberta/mavlink_msg_nav_filter_bias.h @@ -0,0 +1,242 @@ +// MESSAGE NAV_FILTER_BIAS PACKING + +#define MAVLINK_MSG_ID_NAV_FILTER_BIAS 220 + +typedef struct __mavlink_nav_filter_bias_t +{ + uint64_t usec; ///< Timestamp (microseconds) + float accel_0; ///< b_f[0] + float accel_1; ///< b_f[1] + float accel_2; ///< b_f[2] + float gyro_0; ///< b_f[0] + float gyro_1; ///< b_f[1] + float gyro_2; ///< b_f[2] + +} mavlink_nav_filter_bias_t; + + + +/** + * @brief Pack a nav_filter_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 usec Timestamp (microseconds) + * @param accel_0 b_f[0] + * @param accel_1 b_f[1] + * @param accel_2 b_f[2] + * @param gyro_0 b_f[0] + * @param gyro_1 b_f[1] + * @param gyro_2 b_f[2] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_filter_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float accel_0, float accel_1, float accel_2, float gyro_0, float gyro_1, float gyro_2) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_NAV_FILTER_BIAS; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds) + i += put_float_by_index(accel_0, i, msg->payload); // b_f[0] + i += put_float_by_index(accel_1, i, msg->payload); // b_f[1] + i += put_float_by_index(accel_2, i, msg->payload); // b_f[2] + i += put_float_by_index(gyro_0, i, msg->payload); // b_f[0] + i += put_float_by_index(gyro_1, i, msg->payload); // b_f[1] + i += put_float_by_index(gyro_2, i, msg->payload); // b_f[2] + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a nav_filter_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 usec Timestamp (microseconds) + * @param accel_0 b_f[0] + * @param accel_1 b_f[1] + * @param accel_2 b_f[2] + * @param gyro_0 b_f[0] + * @param gyro_1 b_f[1] + * @param gyro_2 b_f[2] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_filter_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float accel_0, float accel_1, float accel_2, float gyro_0, float gyro_1, float gyro_2) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_NAV_FILTER_BIAS; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds) + i += put_float_by_index(accel_0, i, msg->payload); // b_f[0] + i += put_float_by_index(accel_1, i, msg->payload); // b_f[1] + i += put_float_by_index(accel_2, i, msg->payload); // b_f[2] + i += put_float_by_index(gyro_0, i, msg->payload); // b_f[0] + i += put_float_by_index(gyro_1, i, msg->payload); // b_f[1] + i += put_float_by_index(gyro_2, i, msg->payload); // b_f[2] + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a nav_filter_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 nav_filter_bias C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_nav_filter_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_filter_bias_t* nav_filter_bias) +{ + return mavlink_msg_nav_filter_bias_pack(system_id, component_id, msg, nav_filter_bias->usec, nav_filter_bias->accel_0, nav_filter_bias->accel_1, nav_filter_bias->accel_2, nav_filter_bias->gyro_0, nav_filter_bias->gyro_1, nav_filter_bias->gyro_2); +} + +/** + * @brief Send a nav_filter_bias message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds) + * @param accel_0 b_f[0] + * @param accel_1 b_f[1] + * @param accel_2 b_f[2] + * @param gyro_0 b_f[0] + * @param gyro_1 b_f[1] + * @param gyro_2 b_f[2] + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_nav_filter_bias_send(mavlink_channel_t chan, uint64_t usec, float accel_0, float accel_1, float accel_2, float gyro_0, float gyro_1, float gyro_2) +{ + mavlink_message_t msg; + mavlink_msg_nav_filter_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, accel_0, accel_1, accel_2, gyro_0, gyro_1, gyro_2); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE NAV_FILTER_BIAS UNPACKING + +/** + * @brief Get field usec from nav_filter_bias message + * + * @return Timestamp (microseconds) + */ +static inline uint64_t mavlink_msg_nav_filter_bias_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field accel_0 from nav_filter_bias message + * + * @return b_f[0] + */ +static inline float mavlink_msg_nav_filter_bias_get_accel_0(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; +} + +/** + * @brief Get field accel_1 from nav_filter_bias message + * + * @return b_f[1] + */ +static inline float mavlink_msg_nav_filter_bias_get_accel_1(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; +} + +/** + * @brief Get field accel_2 from nav_filter_bias message + * + * @return b_f[2] + */ +static inline float mavlink_msg_nav_filter_bias_get_accel_2(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; +} + +/** + * @brief Get field gyro_0 from nav_filter_bias message + * + * @return b_f[0] + */ +static inline float mavlink_msg_nav_filter_bias_get_gyro_0(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field gyro_1 from nav_filter_bias message + * + * @return b_f[1] + */ +static inline float mavlink_msg_nav_filter_bias_get_gyro_1(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field gyro_2 from nav_filter_bias message + * + * @return b_f[2] + */ +static inline float mavlink_msg_nav_filter_bias_get_gyro_2(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Decode a nav_filter_bias message into a struct + * + * @param msg The message to decode + * @param nav_filter_bias C-struct to decode the message contents into + */ +static inline void mavlink_msg_nav_filter_bias_decode(const mavlink_message_t* msg, mavlink_nav_filter_bias_t* nav_filter_bias) +{ + nav_filter_bias->usec = mavlink_msg_nav_filter_bias_get_usec(msg); + nav_filter_bias->accel_0 = mavlink_msg_nav_filter_bias_get_accel_0(msg); + nav_filter_bias->accel_1 = mavlink_msg_nav_filter_bias_get_accel_1(msg); + nav_filter_bias->accel_2 = mavlink_msg_nav_filter_bias_get_accel_2(msg); + nav_filter_bias->gyro_0 = mavlink_msg_nav_filter_bias_get_gyro_0(msg); + nav_filter_bias->gyro_1 = mavlink_msg_nav_filter_bias_get_gyro_1(msg); + nav_filter_bias->gyro_2 = mavlink_msg_nav_filter_bias_get_gyro_2(msg); +} diff --git a/thirdParty/mavlink/include/ualberta/mavlink_msg_radio_calibration.h b/thirdParty/mavlink/include/ualberta/mavlink_msg_radio_calibration.h new file mode 100644 index 0000000000000000000000000000000000000000..7a599ac714bdedbf6f7846aac42663724bfa756e --- /dev/null +++ b/thirdParty/mavlink/include/ualberta/mavlink_msg_radio_calibration.h @@ -0,0 +1,204 @@ +// MESSAGE RADIO_CALIBRATION PACKING + +#define MAVLINK_MSG_ID_RADIO_CALIBRATION 222 + +typedef struct __mavlink_radio_calibration_t +{ + float aileron[3]; ///< Aileron setpoints: high, center, low + float elevator[3]; ///< Elevator setpoints: high, center, low + float rudder[3]; ///< Rudder setpoints: high, center, low + float gyro[2]; ///< Tail gyro mode/gain setpoints: heading hold, rate mode + float pitch[5]; ///< Pitch curve setpoints (every 25%) + float throttle[5]; ///< Throttle curve setpoints (every 25%) + +} mavlink_radio_calibration_t; + +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN 3 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN 3 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN 3 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN 2 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN 5 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN 5 + + +/** + * @brief Pack a radio_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 aileron Aileron setpoints: high, center, low + * @param elevator Elevator setpoints: high, center, low + * @param rudder Rudder setpoints: high, center, low + * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode + * @param pitch Pitch curve setpoints (every 25%) + * @param throttle Throttle curve setpoints (every 25%) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* aileron, const float* elevator, const float* rudder, const float* gyro, const float* pitch, const float* throttle) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION; + + i += put_array_by_index((const int8_t*)aileron, sizeof(float)*3, i, msg->payload); // Aileron setpoints: high, center, low + i += put_array_by_index((const int8_t*)elevator, sizeof(float)*3, i, msg->payload); // Elevator setpoints: high, center, low + i += put_array_by_index((const int8_t*)rudder, sizeof(float)*3, i, msg->payload); // Rudder setpoints: high, center, low + i += put_array_by_index((const int8_t*)gyro, sizeof(float)*2, i, msg->payload); // Tail gyro mode/gain setpoints: heading hold, rate mode + i += put_array_by_index((const int8_t*)pitch, sizeof(float)*5, i, msg->payload); // Pitch curve setpoints (every 25%) + i += put_array_by_index((const int8_t*)throttle, sizeof(float)*5, i, msg->payload); // Throttle curve setpoints (every 25%) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a radio_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 aileron Aileron setpoints: high, center, low + * @param elevator Elevator setpoints: high, center, low + * @param rudder Rudder setpoints: high, center, low + * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode + * @param pitch Pitch curve setpoints (every 25%) + * @param throttle Throttle curve setpoints (every 25%) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_calibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* aileron, const float* elevator, const float* rudder, const float* gyro, const float* pitch, const float* throttle) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION; + + i += put_array_by_index((const int8_t*)aileron, sizeof(float)*3, i, msg->payload); // Aileron setpoints: high, center, low + i += put_array_by_index((const int8_t*)elevator, sizeof(float)*3, i, msg->payload); // Elevator setpoints: high, center, low + i += put_array_by_index((const int8_t*)rudder, sizeof(float)*3, i, msg->payload); // Rudder setpoints: high, center, low + i += put_array_by_index((const int8_t*)gyro, sizeof(float)*2, i, msg->payload); // Tail gyro mode/gain setpoints: heading hold, rate mode + i += put_array_by_index((const int8_t*)pitch, sizeof(float)*5, i, msg->payload); // Pitch curve setpoints (every 25%) + i += put_array_by_index((const int8_t*)throttle, sizeof(float)*5, i, msg->payload); // Throttle curve setpoints (every 25%) + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a radio_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 radio_calibration C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_radio_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_calibration_t* radio_calibration) +{ + return mavlink_msg_radio_calibration_pack(system_id, component_id, msg, radio_calibration->aileron, radio_calibration->elevator, radio_calibration->rudder, radio_calibration->gyro, radio_calibration->pitch, radio_calibration->throttle); +} + +/** + * @brief Send a radio_calibration message + * @param chan MAVLink channel to send the message + * + * @param aileron Aileron setpoints: high, center, low + * @param elevator Elevator setpoints: high, center, low + * @param rudder Rudder setpoints: high, center, low + * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode + * @param pitch Pitch curve setpoints (every 25%) + * @param throttle Throttle curve setpoints (every 25%) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_radio_calibration_send(mavlink_channel_t chan, const float* aileron, const float* elevator, const float* rudder, const float* gyro, const float* pitch, const float* throttle) +{ + mavlink_message_t msg; + mavlink_msg_radio_calibration_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, aileron, elevator, rudder, gyro, pitch, throttle); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE RADIO_CALIBRATION UNPACKING + +/** + * @brief Get field aileron from radio_calibration message + * + * @return Aileron setpoints: high, center, low + */ +static inline uint16_t mavlink_msg_radio_calibration_get_aileron(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload, sizeof(float)*3); + return sizeof(float)*3; +} + +/** + * @brief Get field elevator from radio_calibration message + * + * @return Elevator setpoints: high, center, low + */ +static inline uint16_t mavlink_msg_radio_calibration_get_elevator(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(float)*3, sizeof(float)*3); + return sizeof(float)*3; +} + +/** + * @brief Get field rudder from radio_calibration message + * + * @return Rudder setpoints: high, center, low + */ +static inline uint16_t mavlink_msg_radio_calibration_get_rudder(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3, sizeof(float)*3); + return sizeof(float)*3; +} + +/** + * @brief Get field gyro from radio_calibration message + * + * @return Tail gyro mode/gain setpoints: heading hold, rate mode + */ +static inline uint16_t mavlink_msg_radio_calibration_get_gyro(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3+sizeof(float)*3, sizeof(float)*2); + return sizeof(float)*2; +} + +/** + * @brief Get field pitch from radio_calibration message + * + * @return Pitch curve setpoints (every 25%) + */ +static inline uint16_t mavlink_msg_radio_calibration_get_pitch(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3+sizeof(float)*3+sizeof(float)*2, sizeof(float)*5); + return sizeof(float)*5; +} + +/** + * @brief Get field throttle from radio_calibration message + * + * @return Throttle curve setpoints (every 25%) + */ +static inline uint16_t mavlink_msg_radio_calibration_get_throttle(const mavlink_message_t* msg, float* r_data) +{ + + memcpy(r_data, msg->payload+sizeof(float)*3+sizeof(float)*3+sizeof(float)*3+sizeof(float)*2+sizeof(float)*5, sizeof(float)*5); + return sizeof(float)*5; +} + +/** + * @brief Decode a radio_calibration message into a struct + * + * @param msg The message to decode + * @param radio_calibration C-struct to decode the message contents into + */ +static inline void mavlink_msg_radio_calibration_decode(const mavlink_message_t* msg, mavlink_radio_calibration_t* radio_calibration) +{ + mavlink_msg_radio_calibration_get_aileron(msg, radio_calibration->aileron); + mavlink_msg_radio_calibration_get_elevator(msg, radio_calibration->elevator); + mavlink_msg_radio_calibration_get_rudder(msg, radio_calibration->rudder); + mavlink_msg_radio_calibration_get_gyro(msg, radio_calibration->gyro); + mavlink_msg_radio_calibration_get_pitch(msg, radio_calibration->pitch); + mavlink_msg_radio_calibration_get_throttle(msg, radio_calibration->throttle); +} diff --git a/thirdParty/mavlink/include/ualberta/mavlink_msg_request_rc_channels.h b/thirdParty/mavlink/include/ualberta/mavlink_msg_request_rc_channels.h new file mode 100644 index 0000000000000000000000000000000000000000..64202ffe269eb434aa80960924793f92c38e25d2 --- /dev/null +++ b/thirdParty/mavlink/include/ualberta/mavlink_msg_request_rc_channels.h @@ -0,0 +1,101 @@ +// MESSAGE REQUEST_RC_CHANNELS PACKING + +#define MAVLINK_MSG_ID_REQUEST_RC_CHANNELS 221 + +typedef struct __mavlink_request_rc_channels_t +{ + uint8_t enabled; ///< True: start sending data; False: stop sending data + +} mavlink_request_rc_channels_t; + + + +/** + * @brief Pack a request_rc_channels 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 enabled True: start sending data; False: stop sending data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t enabled) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_REQUEST_RC_CHANNELS; + + i += put_uint8_t_by_index(enabled, i, msg->payload); // True: start sending data; False: stop sending data + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a request_rc_channels 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 enabled True: start sending data; False: stop sending data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enabled) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_REQUEST_RC_CHANNELS; + + i += put_uint8_t_by_index(enabled, i, msg->payload); // True: start sending data; False: stop sending data + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a request_rc_channels 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_rc_channels C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_request_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_rc_channels_t* request_rc_channels) +{ + return mavlink_msg_request_rc_channels_pack(system_id, component_id, msg, request_rc_channels->enabled); +} + +/** + * @brief Send a request_rc_channels message + * @param chan MAVLink channel to send the message + * + * @param enabled True: start sending data; False: stop sending data + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_rc_channels_send(mavlink_channel_t chan, uint8_t enabled) +{ + mavlink_message_t msg; + mavlink_msg_request_rc_channels_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, enabled); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE REQUEST_RC_CHANNELS UNPACKING + +/** + * @brief Get field enabled from request_rc_channels message + * + * @return True: start sending data; False: stop sending data + */ +static inline uint8_t mavlink_msg_request_rc_channels_get_enabled(const mavlink_message_t* msg) +{ + return (uint8_t)(msg->payload)[0]; +} + +/** + * @brief Decode a request_rc_channels message into a struct + * + * @param msg The message to decode + * @param request_rc_channels C-struct to decode the message contents into + */ +static inline void mavlink_msg_request_rc_channels_decode(const mavlink_message_t* msg, mavlink_request_rc_channels_t* request_rc_channels) +{ + request_rc_channels->enabled = mavlink_msg_request_rc_channels_get_enabled(msg); +} diff --git a/thirdParty/mavlink/include/ualberta/ualberta.h b/thirdParty/mavlink/include/ualberta/ualberta.h new file mode 100644 index 0000000000000000000000000000000000000000..e9f238b802f0d3dd10f91c65d0e28b17f34e4013 --- /dev/null +++ b/thirdParty/mavlink/include/ualberta/ualberta.h @@ -0,0 +1,42 @@ +/** @file + * @brief MAVLink comm protocol. + * @see http://pixhawk.ethz.ch/software/mavlink + * Generated on Thursday, March 31 2011, 22:06 UTC + */ +#ifndef UALBERTA_H +#define UALBERTA_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "../protocol.h" + +#define MAVLINK_ENABLED_UALBERTA + + +#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 + + +// MESSAGE DEFINITIONS + +#include "./mavlink_msg_nav_filter_bias.h" +#include "./mavlink_msg_request_rc_channels.h" +#include "./mavlink_msg_radio_calibration.h" +#ifdef __cplusplus +} +#endif +#endif diff --git a/thirdParty/mavlink/license.txt b/thirdParty/mavlink/license.txt new file mode 100644 index 0000000000000000000000000000000000000000..65c5ca88a67c30becee01c5a8816d964b03862f9 --- /dev/null +++ b/thirdParty/mavlink/license.txt @@ -0,0 +1,165 @@ + GNU LESSER GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + + This version of the GNU Lesser General Public License incorporates +the terms and conditions of version 3 of the GNU General Public +License, supplemented by the additional permissions listed below. + + 0. Additional Definitions. + + As used herein, "this License" refers to version 3 of the GNU Lesser +General Public License, and the "GNU GPL" refers to version 3 of the GNU +General Public License. + + "The Library" refers to a covered work governed by this License, +other than an Application or a Combined Work as defined below. + + An "Application" is any work that makes use of an interface provided +by the Library, but which is not otherwise based on the Library. +Defining a subclass of a class defined by the Library is deemed a mode +of using an interface provided by the Library. + + A "Combined Work" is a work produced by combining or linking an +Application with the Library. The particular version of the Library +with which the Combined Work was made is also called the "Linked +Version". + + The "Minimal Corresponding Source" for a Combined Work means the +Corresponding Source for the Combined Work, excluding any source code +for portions of the Combined Work that, considered in isolation, are +based on the Application, and not on the Linked Version. + + The "Corresponding Application Code" for a Combined Work means the +object code and/or source code for the Application, including any data +and utility programs needed for reproducing the Combined Work from the +Application, but excluding the System Libraries of the Combined Work. + + 1. Exception to Section 3 of the GNU GPL. + + You may convey a covered work under sections 3 and 4 of this License +without being bound by section 3 of the GNU GPL. + + 2. Conveying Modified Versions. + + If you modify a copy of the Library, and, in your modifications, a +facility refers to a function or data to be supplied by an Application +that uses the facility (other than as an argument passed when the +facility is invoked), then you may convey a copy of the modified +version: + + a) under this License, provided that you make a good faith effort to + ensure that, in the event an Application does not supply the + function or data, the facility still operates, and performs + whatever part of its purpose remains meaningful, or + + b) under the GNU GPL, with none of the additional permissions of + this License applicable to that copy. + + 3. Object Code Incorporating Material from Library Header Files. + + The object code form of an Application may incorporate material from +a header file that is part of the Library. You may convey such object +code under terms of your choice, provided that, if the incorporated +material is not limited to numerical parameters, data structure +layouts and accessors, or small macros, inline functions and templates +(ten or fewer lines in length), you do both of the following: + + a) Give prominent notice with each copy of the object code that the + Library is used in it and that the Library and its use are + covered by this License. + + b) Accompany the object code with a copy of the GNU GPL and this license + document. + + 4. Combined Works. + + You may convey a Combined Work under terms of your choice that, +taken together, effectively do not restrict modification of the +portions of the Library contained in the Combined Work and reverse +engineering for debugging such modifications, if you also do each of +the following: + + a) Give prominent notice with each copy of the Combined Work that + the Library is used in it and that the Library and its use are + covered by this License. + + b) Accompany the Combined Work with a copy of the GNU GPL and this license + document. + + c) For a Combined Work that displays copyright notices during + execution, include the copyright notice for the Library among + these notices, as well as a reference directing the user to the + copies of the GNU GPL and this license document. + + d) Do one of the following: + + 0) Convey the Minimal Corresponding Source under the terms of this + License, and the Corresponding Application Code in a form + suitable for, and under terms that permit, the user to + recombine or relink the Application with a modified version of + the Linked Version to produce a modified Combined Work, in the + manner specified by section 6 of the GNU GPL for conveying + Corresponding Source. + + 1) Use a suitable shared library mechanism for linking with the + Library. A suitable mechanism is one that (a) uses at run time + a copy of the Library already present on the user's computer + system, and (b) will operate properly with a modified version + of the Library that is interface-compatible with the Linked + Version. + + e) Provide Installation Information, but only if you would otherwise + be required to provide such information under section 6 of the + GNU GPL, and only to the extent that such information is + necessary to install and execute a modified version of the + Combined Work produced by recombining or relinking the + Application with a modified version of the Linked Version. (If + you use option 4d0, the Installation Information must accompany + the Minimal Corresponding Source and Corresponding Application + Code. If you use option 4d1, you must provide the Installation + Information in the manner specified by section 6 of the GNU GPL + for conveying Corresponding Source.) + + 5. Combined Libraries. + + You may place library facilities that are a work based on the +Library side by side in a single library together with other library +facilities that are not Applications and are not covered by this +License, and convey such a combined library under terms of your +choice, if you do both of the following: + + a) Accompany the combined library with a copy of the same work based + on the Library, uncombined with any other library facilities, + conveyed under the terms of this License. + + b) Give prominent notice with the combined library that part of it + is a work based on the Library, and explaining where to find the + accompanying uncombined form of the same work. + + 6. Revised Versions of the GNU Lesser General Public License. + + The Free Software Foundation may publish revised and/or new versions +of the GNU Lesser General Public License from time to time. Such new +versions will be similar in spirit to the present version, but may +differ in detail to address new problems or concerns. + + Each version is given a distinguishing version number. If the +Library as you received it specifies that a certain numbered version +of the GNU Lesser General Public License "or any later version" +applies to it, you have the option of following the terms and +conditions either of that published version or of any later version +published by the Free Software Foundation. If the Library as you +received it does not specify a version number of the GNU Lesser +General Public License, you may choose any version of the GNU Lesser +General Public License ever published by the Free Software Foundation. + + If the Library as you received it specifies that a proxy can decide +whether future versions of the GNU Lesser General Public License shall +apply, that proxy's public statement of acceptance of any version is +permanent authorization for you to choose that version for the +Library. diff --git a/thirdParty/mavlink/message_definitions/ardupilotmega.xml b/thirdParty/mavlink/message_definitions/ardupilotmega.xml new file mode 100644 index 0000000000000000000000000000000000000000..39d96eab515cf9fb19b6fdf0bf167e369be00a50 --- /dev/null +++ b/thirdParty/mavlink/message_definitions/ardupilotmega.xml @@ -0,0 +1,6 @@ + + + common.xml + + + diff --git a/thirdParty/mavlink/message_definitions/common.xml b/thirdParty/mavlink/message_definitions/common.xml new file mode 100644 index 0000000000000000000000000000000000000000..85e0df66e340bd8447dd4432c0d8edd47d715262 --- /dev/null +++ b/thirdParty/mavlink/message_definitions/common.xml @@ -0,0 +1,876 @@ + + +2 + + + + Commands to be executed by the MAV. They can be executed on user request, + or as part of a mission script. If the action is used in a mission, the parameter mapping + to the waypoint/mission message is as follows: + Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what + ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. + + Navigate to waypoint. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing) + Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached) + 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. + Desired yaw angle at waypoint (rotary wing) + Latitude + Longitude + Altitude + + + Loiter around this waypoint an unlimited amount of time + Empty + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this waypoint for X turns + Turns + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this waypoint for X seconds + Seconds (decimal) + Empty + Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Return to launch location + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Land at location + Empty + Empty + Empty + Desired yaw angle. + Latitude + Longitude + Altitude + + + Takeoff from ground / hand + Minimum pitch (if airspeed sensor present), desired pitch without sensor + Empty + Empty + Yaw angle (if magnetometer present), ignored without magnetometer + Latitude + Longitude + Altitude + + + Set the location the system should be heading towards (camera heads or + rotary wing aircraft). + Empty + Empty + Empty + Empty + Latitude + Longitude + Altitude + + + Control autonomous path planning on the MAV. + 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning + 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid + Empty + Yaw angle at goal, in compass degrees, [0..360] + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Delay mission state machine. + Delay in seconds (decimal) + Empty + Empty + Empty + Empty + Empty + Empty + + + Ascend/descend at rate. Delay mission state machine until desired altitude reached. + Descent / Ascend rate (m/s) + Empty + Empty + Empty + Empty + Empty + Finish Altitude + + + Delay mission state machine until within desired distance of next NAV point. + Distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + Reach a certain target angle. + target angle: [0-360], 0 is north + speed during yaw change:[deg per second] + direction: negative: counter clockwise, positive: clockwise [-1,1] + relative offset or absolute angle: [ 1,0] + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Set system mode. + Mode, as defined by ENUM MAV_MODE + Empty + Empty + Empty + Empty + Empty + Empty + + + Jump to the desired command in the mission list. Repeat this action only the specified number of times + Sequence number + Repeat count + Empty + Empty + Empty + Empty + Empty + + + Change speed and/or throttle set points. + Speed type (0=Airspeed, 1=Ground Speed) + Speed (m/s, -1 indicates no change) + Throttle ( Percent, -1 indicates no change) + Empty + Empty + Empty + Empty + + + Changes the home location either to the current location or a specified location. + Use current (1=use current location, 0=use specified location) + Empty + Empty + Empty + Latitude + Longitude + Altitude + + + Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. + Parameter number + Parameter value + Empty + Empty + Empty + Empty + Empty + + + Set a relay to a condition. + Relay number + Setting (1=on, 0=off, others possible depending on system hardware) + Empty + Empty + Empty + Empty + Empty + + + Cycle a relay on and off for a desired number of cyles with a desired period. + Relay number + Cycle count + Cycle time (seconds, decimal) + Empty + Empty + Empty + Empty + + + Set a servo to a desired PWM value. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Empty + Empty + Empty + Empty + Empty + + + Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Cycle count + Cycle time (seconds) + Empty + Empty + Empty + + + Control onboard camera system. + Camera ID (-1 for all) + Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw + Transmission mode: 0: video stream, >0: single images every n seconds (decimal) + Recording: 0: disabled, 1: enabled compressed, 2: enabled raw + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the DO commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Trigger calibration. This command will be only accepted if in pre-flight mode. + Gyro calibration: 0: no, 1: yes + Magnetometer calibration: 0: no, 1: yes + Ground pressure: 0: no, 1: yes + Radio calibration: 0: no, 1: yes + Empty + Empty + Empty + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM + Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM + Reserved + Reserved + Empty + Empty + Empty + + + + Data stream IDs. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. + + Enable all data streams + Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. + Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS + Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW + Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. + Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. + Dependent on the autopilot + Dependent on the autopilot + Dependent on the autopilot + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + MAVLink version + + + + The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. + The onboard software version + + + + The system time is the time of the master clock, typically the computer clock of the main onboard computer. + Timestamp of the master clock in microseconds since UNIX epoch. + + + + A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. + PING sequence + 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + Unix timestamp in microseconds + + + + UTC date and time from GPS module + GPS UTC date ddmmyy + GPS UTC time hhmmss + + + + Request to control this MAV + System the GCS requests control for + 0: request control of this MAV, 1: Release control of this MAV + 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + + + + Accept / deny control of this MAV + ID of the GCS this message + 0: request control of this MAV, 1: Release control of this MAV + 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + + + + 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. + key + + + + 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 + The action id + 0: Action DENIED, 1: Action executed + + + + An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h + The system executing the action + The component executing the action + The action id + + + + Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. + The system setting the mode + The new mode + + + + Set the system navigation mode, as defined by enum MAV_NAV_MODE in mavlink/include/mavlink_types.h. The navigation mode applies to the whole aircraft and thus all components. + The system setting the mode + The new navigation mode + + + + Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. + System ID + Component ID + Onboard parameter id + Parameter index. Send -1 to use the param ID field as identifier + + + + Request all parameters of this component. After his request, all parameters are emitted. + System ID + Component ID + + + + Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. + Onboard parameter id + Onboard parameter value + Total number of onboard parameters + Index of this onboard parameter + + + + Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. + System ID + Component ID + Onboard parameter id + Onboard parameter value + + + + The global position, as returned by the Global Positioning System (GPS). This is +NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame) + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude in 1E7 degrees + Longitude in 1E7 degrees + Altitude in 1E3 meters (millimeters) + GPS HDOP + GPS VDOP + GPS ground speed (m/s) + Compass heading in degrees, 0..360 degrees + + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + + The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. + Number of satellites visible + Global satellite ID + 0: Satellite not used, 1: used for localization + Elevation (0: right on top of receiver, 90: on the horizon) of satellite + Direction of satellite, 0: 0 deg, 255: 360 deg. + Signal to noise ratio of satellite + + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (raw) + Y acceleration (raw) + Z acceleration (raw) + Angular speed around X axis (raw) + Angular speed around Y axis (raw) + Angular speed around Z axis (raw) + X Magnetic field (raw) + Y Magnetic field (raw) + Z Magnetic field (raw) + + + + 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. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (raw) + Differential pressure 1 (raw) + Differential pressure 2 (raw) + Raw Temperature measurement (raw) + + + + The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame) + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + + + + + The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame) + Timestamp (microseconds since unix epoch) + Latitude, in degrees + Longitude, in degrees + Absolute altitude, in meters + X Speed (in Latitude direction, positive: going north) + Y Speed (in Longitude direction, positive: going east) + Z Speed (in Altitude direction, positive: going up) + + + + The global position, as returned by the Global Positioning System (GPS). This is +NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame) + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude in degrees + Longitude in degrees + Altitude in meters + GPS HDOP + GPS VDOP + GPS ground speed + Compass heading in degrees, 0..360 degrees + + + + The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. + System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + Navigation mode, see MAV_NAV_MODE ENUM + System status flag, see MAV_STATUS ENUM + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Battery voltage, in millivolts (1 = 1 millivolt) + Remaining battery energy: (0%: 0, 100%: 1000) + Dropped packets (packets that were corrupted on reception on the MAV) + + + + The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + Receive signal strength indicator, 0: 0%, 255: 100% + + + + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + Receive signal strength indicator, 0: 0%, 255: 100% + + + + The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. + Servo output 1 value, in microseconds + Servo output 2 value, in microseconds + Servo output 3 value, in microseconds + Servo output 4 value, in microseconds + Servo output 5 value, in microseconds + Servo output 6 value, in microseconds + Servo output 7 value, in microseconds + Servo output 8 value, in microseconds + + + + Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on the system. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed, global frame is Z-up, right handed + System ID + Component ID + Sequence + The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + PARAM5 / local: x position, global: latitude + PARAM6 / y position: global: longitude + PARAM7 / z position: global: altitude + + + + Request the information of the waypoint with the sequence number seq. The response of the system to this message should be a WAYPOINT message. + System ID + Component ID + Sequence + + + + Set the waypoint with sequence number seq as current waypoint. This means that the MAV will continue to this waypoint on the shortest path (not following the waypoints in-between). + System ID + Component ID + Sequence + + + + Message that announces the sequence number of the current active waypoint. The MAV will fly towards this waypoint. + Sequence + + + + Request the overall list of waypoints from the system/component. + System ID + Component ID + + + + This message is emitted as response to WAYPOINT_REQUEST_LIST by the MAV. The GCS can then request the individual waypoints based on the knowledge of the total number of waypoints. + System ID + Component ID + Number of Waypoints in the Sequence + + + + Delete all waypoints at once. + System ID + Component ID + + + + A certain waypoint has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint. + Sequence + + + + Ack message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). + System ID + Component ID + 0: OK, 1: Error + + + + 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. + System ID + Component ID + global position * 1E7 + global position * 1E7 + global position * 1000 + + + + Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position + Latitude (WGS84), expressed as * 1E7 + Longitude (WGS84), expressed as * 1E7 + Altitude(WGS84), expressed as * 1000 + + + + Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/waypoint planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message. + System ID + Component ID + x position + y position + z position + Desired yaw angle + + + + Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS. + x position + y position + z position + Desired yaw angle + + + + Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + Attitude estimation health: 0: poor, 255: excellent + 0: Attitude control disabled, 1: enabled + 0: X, Y position control disabled, 1: enabled + 0: Z position control disabled, 1: enabled + 0: Yaw angle control disabled, 1: enabled + + + + Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations. + System ID + Component ID + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + + Read out the safety zone the MAV currently assumes. + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + + The output of the attitude controller. This output is the control response the controller currently generates and the attitude the MAV would take if it is under control of the attitude controller. The primary use of this message is to check the response and signs of the controller before the actual flight. + 1: enabled, 0: disabled + Attitude roll: -128: -100%, 127: +100% + Attitude pitch: -128: -100%, 127: +100% + Attitude yaw: -128: -100%, 127: +100% + Attitude thrust: -128: -100%, 127: +100% + + + + The output of the position controller. The primary use of this message is to check the response and signs of the controller before the actual flight. + 1: enabled, 0: disabled + Position x: -128: -100%, 127: +100% + Position y: -128: -100%, 127: +100% + Position z: -128: -100%, 127: +100% + Position yaw: -128: -100%, 127: +100% + + + + Outputs of the APM navigation controller. The primary use of this message is to check the response and signs +of the controller before actual flight and to assist with tuning controller parameters + Current desired roll in degrees + Current desired pitch in degrees + Current desired heading in degrees + Bearing to current waypoint/target in degrees + Distance to active waypoint in meters + Current altitude error in meters + Current airspeed error in meters/second + Current crosstrack error on x-y plane in meters + + + + The goal position of the system. This position is the input to any navigation or path planning algorithm and does NOT represent the current controller setpoint. + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + + Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle. + x position error + y position error + z position error + roll error (radians) + pitch error (radians) + yaw error (radians) + x velocity + y velocity + z velocity + + + + The system setting the altitude + The new altitude in meters + + + + The target requested to send the message stream. + The target requested to send the message stream. + The ID of the requested message type + The requested interval between two messages of this type + 1 to start sending, 0 to stop sending. + + + + The system to be controlled + roll + pitch + yaw + thrust + roll control enabled auto:0, manual:1 + pitch auto:0, manual:1 + yaw auto:0, manual:1 + thrust auto:0, manual:1 + + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + + + + Metrics typically displayed on a HUD for fixed wing aircraft + Current airspeed in m/s + Current ground speed in m/s + Current heading in degrees, in compass units (0..360, 0=north) + Current throttle setting in integer percent, 0 to 100 + Current altitude (MSL), in meters + Current climb rate in meters/second + + + + Send a command with up to four parameters to the MAV + System which should execute the command + Component which should execute the command, 0 for all components + Command ID, as defined by MAV_CMD enum. + 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + Parameter 1, as defined by MAV_CMD enum. + Parameter 2, as defined by MAV_CMD enum. + Parameter 3, as defined by MAV_CMD enum. + Parameter 4, as defined by MAV_CMD enum. + + + + Report status of a command. Includes feedback wether the command was executed + Current airspeed in m/s + 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + + + + + + + + + Name + Timestamp + x + y + z + + + + Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Name of the debug variable + Floating point value + + + + Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Name of the debug variable + Signed integer value + + + + Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). + Severity of status, 0 = info message, 255 = critical fault + Status text message, without null termination character + + + + Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. + index of debug variable + DEBUG value + + + + diff --git a/thirdParty/mavlink/message_definitions/pixhawk.xml b/thirdParty/mavlink/message_definitions/pixhawk.xml new file mode 100644 index 0000000000000000000000000000000000000000..55e53205aa084fa8c7d1dd7292e5360b4687db48 --- /dev/null +++ b/thirdParty/mavlink/message_definitions/pixhawk.xml @@ -0,0 +1,253 @@ + + +common.xml + + + + Slugs parameter interface subsets + + With comment: PID Pitch parameter + + + + + Content Types for data transmission handshake + + + + + + + + + The system to be controlled + roll + pitch + yaw + thrust + roll control enabled auto:0, manual:1 + pitch auto:0, manual:1 + yaw auto:0, manual:1 + thrust auto:0, manual:1 + + + + Camera id + Camera mode: 0 = auto, 1 = manual + Trigger pin, 0-3 for PtGrey FireFly + Shutter interval, in microseconds + Exposure time, in microseconds + Camera gain + + + + Timestamp + IMU seq + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + Local frame Z coordinate (height over ground) + GPS X coordinate + GPS Y coordinate + Global frame altitude + + + + 0 to disable, 1 to enable + + + + Camera id + Camera # (starts with 0) + Timestamp + Until which timestamp this buffer will stay valid + The image sequence number + Position of the image in the buffer, starts with 0 + Image width + Image height + Image depth + Image channels + Shared memory area key + Exposure time, in microseconds + Camera gain + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + Local frame Z coordinate (height over ground) + GPS X coordinate + GPS Y coordinate + Global frame altitude + + + + Timestamp (milliseconds) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + + Timestamp (milliseconds) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + + Message sent to the MAV to set a new position as reference for the controller + System ID + Component ID + ID of waypoint, 0 for plain position + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + + Message sent to the MAV to set a new offset from the currently controlled position + System ID + Component ID + x position offset + y position offset + z position offset + yaw orientation offset in radians, 0 = NORTH + + + + + ID of waypoint, 0 for plain position + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + + ID + x position + y position + z position + roll orientation + pitch orientation + yaw orientation + + + + ADC1 (J405 ADC3, LPC2148 AD0.6) + ADC2 (J405 ADC5, LPC2148 AD0.2) + ADC3 (J405 ADC6, LPC2148 AD0.1) + ADC4 (J405 ADC7, LPC2148 AD1.3) + Battery voltage + Temperature (degrees celcius) + Barometric pressure (hecto Pascal) + + + + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Number of I2C errors since startup +Number of I2C errors since startup + Number of I2C errors since startup +Number of I2C errors since startup + Number of I2C errors since startup + + + + Watchdog ID + Number of processes + + + + Watchdog ID + Process ID + Process name + Process arguments + Timeout (seconds) + + + + Watchdog ID + Process ID + Is running / finished / suspended / crashed + Is muted + PID + Number of crashes + + + + Target system ID + Watchdog ID + Process ID + Command ID + + + + 0: Pattern, 1: Letter + Confidence of detection + Pattern file name + Accepted as true detection, 0 no, 1 yes + + + + Notifies the operator about a point of interest (POI). This can be anything detected by the + system. This generic message is intented to help interfacing to generic visualizations and to display + the POI on a map. + 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + 0: global, 1:local + 0: no timeout, >1: timeout in seconds + X Position + Y Position + Z Position + POI name + + + + Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the + system. This generic message is intented to help interfacing to generic visualizations and to display + the POI on a map. + 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + 0: global, 1:local + 0: no timeout, >1: timeout in seconds + X1 Position + Y1 Position + Z1 Position + X2 Position + Y2 Position + Z2 Position + POI connection name + + + + type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + total data size in bytes (set on ACK only) + number of packets beeing sent (set on ACK only) + payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + JPEG quality out of [1,100] + + + + sequence number (starting with 0 on every transmission) + image data bytes + + + + x position in m + y position in m + z position in m + Orientation assignment 0: false, 1:true + Size in pixels + Orientation + Descriptor + Harris operator response at this location + + + + diff --git a/thirdParty/mavlink/message_definitions/slugs.xml b/thirdParty/mavlink/message_definitions/slugs.xml new file mode 100644 index 0000000000000000000000000000000000000000..6de0697fef69a78cafeb856f9b4569bb4ae14925 --- /dev/null +++ b/thirdParty/mavlink/message_definitions/slugs.xml @@ -0,0 +1,142 @@ + + +common.xml + + + + + + + Sensor and DSC control loads. + Sensor DSC Load + Control DSC Load + Battery Voltage in millivolts + + + + Air data for altitude and airspeed computation. + Dynamic pressure (Pa) + Static pressure (Pa) + Board temperature + + + + Accelerometer and gyro biases. + Accelerometer X bias (m/s) + Accelerometer Y bias (m/s) + Accelerometer Z bias (m/s) + Gyro X bias (rad/s) + Gyro Y bias (rad/s) + Gyro Z bias (rad/s) + + + + Configurable diagnostic messages. + Diagnostic float 1 + Diagnostic float 2 + Diagnostic float 3 + Diagnostic short 1 + Diagnostic short 2 + Diagnostic short 3 + + + + Data used in the navigation algorithm. + Measured Airspeed prior to the Nav Filter + Commanded Roll + Commanded Pitch + Commanded Turn rate + Y component of the body acceleration + Total Distance to Run on this leg of Navigation + Remaining distance to Run on this leg of Navigation + Origin WP + Destination WP + + + + Configurable data log probes to be used inside Simulink + Log value 1 + Log value 2 + Log value 3 + Log value 4 + Log value 5 + Log value 6 + + + + Pilot console PWM messges. + Year reported by Gps + Month reported by Gps + Day reported by Gps + Hour reported by Gps + Min reported by Gps + Sec reported by Gps + Visible sattelites reported by Gps + + + + Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX. + The system setting the commands + Commanded Airspeed + Log value 2 + Log value 3 + + + +This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows: + Position Bit Code + ================================= + 15-8 Reserved + 7 dt_pass 128 + 6 dla_pass 64 + 5 dra_pass 32 + 4 dr_pass 16 + 3 dle_pass 8 + 2 dre_pass 4 + 1 dlf_pass 2 + 0 drf_pass 1 + Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface. + The system setting the commands + Bitfield containing the PT configuration + + + + + Action messages focused on the SLUGS AP. + The system reporting the action + Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + Value associated with the action + + + + \ No newline at end of file diff --git a/thirdParty/mavlink/message_definitions/ualberta.xml b/thirdParty/mavlink/message_definitions/ualberta.xml new file mode 100644 index 0000000000000000000000000000000000000000..ef28d6e9149516ce156916f0559db5c8ed0c464e --- /dev/null +++ b/thirdParty/mavlink/message_definitions/ualberta.xml @@ -0,0 +1,29 @@ + + + common.xml + + + Accelerometer and Gyro biases from the navigation filter + Timestamp (microseconds) + b_f[0] + b_f[1] + b_f[2] + b_f[0] + b_f[1] + b_f[2] + + + Request raw and normalized rc data from the UAV + True: start sending data; False: stop sending data + + + Complete set of calibration parameters for the radio + Aileron setpoints: high, center, low + Elevator setpoints: high, center, low + Rudder setpoints: high, center, low + Tail gyro mode/gain setpoints: heading hold, rate mode + Pitch curve setpoints (every 25%) + Throttle curve setpoints (every 25%) + + + diff --git a/thirdParty/qserial b/thirdParty/qserial deleted file mode 160000 index 004e3de552fe25fee593dfcb03e2ffa82cb0b152..0000000000000000000000000000000000000000 --- a/thirdParty/qserial +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 004e3de552fe25fee593dfcb03e2ffa82cb0b152 diff --git a/thirdParty/qserialport/COPYING b/thirdParty/qserialport/COPYING new file mode 100644 index 0000000000000000000000000000000000000000..5ab7695ab8cabe0c5c8a814bb0ab1e8066578fbb --- /dev/null +++ b/thirdParty/qserialport/COPYING @@ -0,0 +1,504 @@ + GNU LESSER GENERAL PUBLIC LICENSE + Version 2.1, February 1999 + + Copyright (C) 1991, 1999 Free Software Foundation, Inc. + 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + +[This is the first released version of the Lesser GPL. It also counts + as the successor of the GNU Library Public License, version 2, hence + the version number 2.1.] + + Preamble + + The licenses for most software are designed to take away your +freedom to share and change it. By contrast, the GNU General Public +Licenses are intended to guarantee your freedom to share and change +free software--to make sure the software is free for all its users. + + This license, the Lesser General Public License, applies to some +specially designated software packages--typically libraries--of the +Free Software Foundation and other authors who decide to use it. You +can use it too, but we suggest you first think carefully about whether +this license or the ordinary General Public License is the better +strategy to use in any particular case, based on the explanations below. + + When we speak of free software, we are referring to freedom of use, +not price. Our General Public Licenses are designed to make sure that +you have the freedom to distribute copies of free software (and charge +for this service if you wish); that you receive source code or can get +it if you want it; that you can change the software and use pieces of +it in new free programs; and that you are informed that you can do +these things. + + To protect your rights, we need to make restrictions that forbid +distributors to deny you these rights or to ask you to surrender these +rights. These restrictions translate to certain responsibilities for +you if you distribute copies of the library or if you modify it. + + For example, if you distribute copies of the library, whether gratis +or for a fee, you must give the recipients all the rights that we gave +you. You must make sure that they, too, receive or can get the source +code. If you link other code with the library, you must provide +complete object files to the recipients, so that they can relink them +with the library after making changes to the library and recompiling +it. And you must show them these terms so they know their rights. + + We protect your rights with a two-step method: (1) we copyright the +library, and (2) we offer you this license, which gives you legal +permission to copy, distribute and/or modify the library. + + To protect each distributor, we want to make it very clear that +there is no warranty for the free library. Also, if the library is +modified by someone else and passed on, the recipients should know +that what they have is not the original version, so that the original +author's reputation will not be affected by problems that might be +introduced by others. + + Finally, software patents pose a constant threat to the existence of +any free program. We wish to make sure that a company cannot +effectively restrict the users of a free program by obtaining a +restrictive license from a patent holder. Therefore, we insist that +any patent license obtained for a version of the library must be +consistent with the full freedom of use specified in this license. + + Most GNU software, including some libraries, is covered by the +ordinary GNU General Public License. This license, the GNU Lesser +General Public License, applies to certain designated libraries, and +is quite different from the ordinary General Public License. We use +this license for certain libraries in order to permit linking those +libraries into non-free programs. + + When a program is linked with a library, whether statically or using +a shared library, the combination of the two is legally speaking a +combined work, a derivative of the original library. The ordinary +General Public License therefore permits such linking only if the +entire combination fits its criteria of freedom. The Lesser General +Public License permits more lax criteria for linking other code with +the library. + + We call this license the "Lesser" General Public License because it +does Less to protect the user's freedom than the ordinary General +Public License. It also provides other free software developers Less +of an advantage over competing non-free programs. These disadvantages +are the reason we use the ordinary General Public License for many +libraries. However, the Lesser license provides advantages in certain +special circumstances. + + For example, on rare occasions, there may be a special need to +encourage the widest possible use of a certain library, so that it becomes +a de-facto standard. To achieve this, non-free programs must be +allowed to use the library. A more frequent case is that a free +library does the same job as widely used non-free libraries. In this +case, there is little to gain by limiting the free library to free +software only, so we use the Lesser General Public License. + + In other cases, permission to use a particular library in non-free +programs enables a greater number of people to use a large body of +free software. For example, permission to use the GNU C Library in +non-free programs enables many more people to use the whole GNU +operating system, as well as its variant, the GNU/Linux operating +system. + + Although the Lesser General Public License is Less protective of the +users' freedom, it does ensure that the user of a program that is +linked with the Library has the freedom and the wherewithal to run +that program using a modified version of the Library. + + The precise terms and conditions for copying, distribution and +modification follow. Pay close attention to the difference between a +"work based on the library" and a "work that uses the library". The +former contains code derived from the library, whereas the latter must +be combined with the library in order to run. + + GNU LESSER GENERAL PUBLIC LICENSE + TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION + + 0. This License Agreement applies to any software library or other +program which contains a notice placed by the copyright holder or +other authorized party saying it may be distributed under the terms of +this Lesser General Public License (also called "this License"). +Each licensee is addressed as "you". + + A "library" means a collection of software functions and/or data +prepared so as to be conveniently linked with application programs +(which use some of those functions and data) to form executables. + + The "Library", below, refers to any such software library or work +which has been distributed under these terms. A "work based on the +Library" means either the Library or any derivative work under +copyright law: that is to say, a work containing the Library or a +portion of it, either verbatim or with modifications and/or translated +straightforwardly into another language. (Hereinafter, translation is +included without limitation in the term "modification".) + + "Source code" for a work means the preferred form of the work for +making modifications to it. For a library, complete source code means +all the source code for all modules it contains, plus any associated +interface definition files, plus the scripts used to control compilation +and installation of the library. + + Activities other than copying, distribution and modification are not +covered by this License; they are outside its scope. The act of +running a program using the Library is not restricted, and output from +such a program is covered only if its contents constitute a work based +on the Library (independent of the use of the Library in a tool for +writing it). Whether that is true depends on what the Library does +and what the program that uses the Library does. + + 1. You may copy and distribute verbatim copies of the Library's +complete source code as you receive it, in any medium, provided that +you conspicuously and appropriately publish on each copy an +appropriate copyright notice and disclaimer of warranty; keep intact +all the notices that refer to this License and to the absence of any +warranty; and distribute a copy of this License along with the +Library. + + You may charge a fee for the physical act of transferring a copy, +and you may at your option offer warranty protection in exchange for a +fee. + + 2. You may modify your copy or copies of the Library or any portion +of it, thus forming a work based on the Library, and copy and +distribute such modifications or work under the terms of Section 1 +above, provided that you also meet all of these conditions: + + a) The modified work must itself be a software library. + + b) You must cause the files modified to carry prominent notices + stating that you changed the files and the date of any change. + + c) You must cause the whole of the work to be licensed at no + charge to all third parties under the terms of this License. + + d) If a facility in the modified Library refers to a function or a + table of data to be supplied by an application program that uses + the facility, other than as an argument passed when the facility + is invoked, then you must make a good faith effort to ensure that, + in the event an application does not supply such function or + table, the facility still operates, and performs whatever part of + its purpose remains meaningful. + + (For example, a function in a library to compute square roots has + a purpose that is entirely well-defined independent of the + application. Therefore, Subsection 2d requires that any + application-supplied function or table used by this function must + be optional: if the application does not supply it, the square + root function must still compute square roots.) + +These requirements apply to the modified work as a whole. If +identifiable sections of that work are not derived from the Library, +and can be reasonably considered independent and separate works in +themselves, then this License, and its terms, do not apply to those +sections when you distribute them as separate works. But when you +distribute the same sections as part of a whole which is a work based +on the Library, the distribution of the whole must be on the terms of +this License, whose permissions for other licensees extend to the +entire whole, and thus to each and every part regardless of who wrote +it. + +Thus, it is not the intent of this section to claim rights or contest +your rights to work written entirely by you; rather, the intent is to +exercise the right to control the distribution of derivative or +collective works based on the Library. + +In addition, mere aggregation of another work not based on the Library +with the Library (or with a work based on the Library) on a volume of +a storage or distribution medium does not bring the other work under +the scope of this License. + + 3. You may opt to apply the terms of the ordinary GNU General Public +License instead of this License to a given copy of the Library. To do +this, you must alter all the notices that refer to this License, so +that they refer to the ordinary GNU General Public License, version 2, +instead of to this License. (If a newer version than version 2 of the +ordinary GNU General Public License has appeared, then you can specify +that version instead if you wish.) Do not make any other change in +these notices. + + Once this change is made in a given copy, it is irreversible for +that copy, so the ordinary GNU General Public License applies to all +subsequent copies and derivative works made from that copy. + + This option is useful when you wish to copy part of the code of +the Library into a program that is not a library. + + 4. You may copy and distribute the Library (or a portion or +derivative of it, under Section 2) in object code or executable form +under the terms of Sections 1 and 2 above provided that you accompany +it with the complete corresponding machine-readable source code, which +must be distributed under the terms of Sections 1 and 2 above on a +medium customarily used for software interchange. + + If distribution of object code is made by offering access to copy +from a designated place, then offering equivalent access to copy the +source code from the same place satisfies the requirement to +distribute the source code, even though third parties are not +compelled to copy the source along with the object code. + + 5. A program that contains no derivative of any portion of the +Library, but is designed to work with the Library by being compiled or +linked with it, is called a "work that uses the Library". Such a +work, in isolation, is not a derivative work of the Library, and +therefore falls outside the scope of this License. + + However, linking a "work that uses the Library" with the Library +creates an executable that is a derivative of the Library (because it +contains portions of the Library), rather than a "work that uses the +library". The executable is therefore covered by this License. +Section 6 states terms for distribution of such executables. + + When a "work that uses the Library" uses material from a header file +that is part of the Library, the object code for the work may be a +derivative work of the Library even though the source code is not. +Whether this is true is especially significant if the work can be +linked without the Library, or if the work is itself a library. The +threshold for this to be true is not precisely defined by law. + + If such an object file uses only numerical parameters, data +structure layouts and accessors, and small macros and small inline +functions (ten lines or less in length), then the use of the object +file is unrestricted, regardless of whether it is legally a derivative +work. (Executables containing this object code plus portions of the +Library will still fall under Section 6.) + + Otherwise, if the work is a derivative of the Library, you may +distribute the object code for the work under the terms of Section 6. +Any executables containing that work also fall under Section 6, +whether or not they are linked directly with the Library itself. + + 6. As an exception to the Sections above, you may also combine or +link a "work that uses the Library" with the Library to produce a +work containing portions of the Library, and distribute that work +under terms of your choice, provided that the terms permit +modification of the work for the customer's own use and reverse +engineering for debugging such modifications. + + You must give prominent notice with each copy of the work that the +Library is used in it and that the Library and its use are covered by +this License. You must supply a copy of this License. If the work +during execution displays copyright notices, you must include the +copyright notice for the Library among them, as well as a reference +directing the user to the copy of this License. Also, you must do one +of these things: + + a) Accompany the work with the complete corresponding + machine-readable source code for the Library including whatever + changes were used in the work (which must be distributed under + Sections 1 and 2 above); and, if the work is an executable linked + with the Library, with the complete machine-readable "work that + uses the Library", as object code and/or source code, so that the + user can modify the Library and then relink to produce a modified + executable containing the modified Library. (It is understood + that the user who changes the contents of definitions files in the + Library will not necessarily be able to recompile the application + to use the modified definitions.) + + b) Use a suitable shared library mechanism for linking with the + Library. A suitable mechanism is one that (1) uses at run time a + copy of the library already present on the user's computer system, + rather than copying library functions into the executable, and (2) + will operate properly with a modified version of the library, if + the user installs one, as long as the modified version is + interface-compatible with the version that the work was made with. + + c) Accompany the work with a written offer, valid for at + least three years, to give the same user the materials + specified in Subsection 6a, above, for a charge no more + than the cost of performing this distribution. + + d) If distribution of the work is made by offering access to copy + from a designated place, offer equivalent access to copy the above + specified materials from the same place. + + e) Verify that the user has already received a copy of these + materials or that you have already sent this user a copy. + + For an executable, the required form of the "work that uses the +Library" must include any data and utility programs needed for +reproducing the executable from it. However, as a special exception, +the materials to be distributed need not include anything that is +normally distributed (in either source or binary form) with the major +components (compiler, kernel, and so on) of the operating system on +which the executable runs, unless that component itself accompanies +the executable. + + It may happen that this requirement contradicts the license +restrictions of other proprietary libraries that do not normally +accompany the operating system. Such a contradiction means you cannot +use both them and the Library together in an executable that you +distribute. + + 7. You may place library facilities that are a work based on the +Library side-by-side in a single library together with other library +facilities not covered by this License, and distribute such a combined +library, provided that the separate distribution of the work based on +the Library and of the other library facilities is otherwise +permitted, and provided that you do these two things: + + a) Accompany the combined library with a copy of the same work + based on the Library, uncombined with any other library + facilities. This must be distributed under the terms of the + Sections above. + + b) Give prominent notice with the combined library of the fact + that part of it is a work based on the Library, and explaining + where to find the accompanying uncombined form of the same work. + + 8. You may not copy, modify, sublicense, link with, or distribute +the Library except as expressly provided under this License. Any +attempt otherwise to copy, modify, sublicense, link with, or +distribute the Library is void, and will automatically terminate your +rights under this License. However, parties who have received copies, +or rights, from you under this License will not have their licenses +terminated so long as such parties remain in full compliance. + + 9. You are not required to accept this License, since you have not +signed it. However, nothing else grants you permission to modify or +distribute the Library or its derivative works. These actions are +prohibited by law if you do not accept this License. Therefore, by +modifying or distributing the Library (or any work based on the +Library), you indicate your acceptance of this License to do so, and +all its terms and conditions for copying, distributing or modifying +the Library or works based on it. + + 10. Each time you redistribute the Library (or any work based on the +Library), the recipient automatically receives a license from the +original licensor to copy, distribute, link with or modify the Library +subject to these terms and conditions. You may not impose any further +restrictions on the recipients' exercise of the rights granted herein. +You are not responsible for enforcing compliance by third parties with +this License. + + 11. If, as a consequence of a court judgment or allegation of patent +infringement or for any other reason (not limited to patent issues), +conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot +distribute so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you +may not distribute the Library at all. For example, if a patent +license would not permit royalty-free redistribution of the Library by +all those who receive copies directly or indirectly through you, then +the only way you could satisfy both it and this License would be to +refrain entirely from distribution of the Library. + +If any portion of this section is held invalid or unenforceable under any +particular circumstance, the balance of the section is intended to apply, +and the section as a whole is intended to apply in other circumstances. + +It is not the purpose of this section to induce you to infringe any +patents or other property right claims or to contest validity of any +such claims; this section has the sole purpose of protecting the +integrity of the free software distribution system which is +implemented by public license practices. Many people have made +generous contributions to the wide range of software distributed +through that system in reliance on consistent application of that +system; it is up to the author/donor to decide if he or she is willing +to distribute software through any other system and a licensee cannot +impose that choice. + +This section is intended to make thoroughly clear what is believed to +be a consequence of the rest of this License. + + 12. If the distribution and/or use of the Library is restricted in +certain countries either by patents or by copyrighted interfaces, the +original copyright holder who places the Library under this License may add +an explicit geographical distribution limitation excluding those countries, +so that distribution is permitted only in or among countries not thus +excluded. In such case, this License incorporates the limitation as if +written in the body of this License. + + 13. The Free Software Foundation may publish revised and/or new +versions of the Lesser General Public License from time to time. +Such new versions will be similar in spirit to the present version, +but may differ in detail to address new problems or concerns. + +Each version is given a distinguishing version number. If the Library +specifies a version number of this License which applies to it and +"any later version", you have the option of following the terms and +conditions either of that version or of any later version published by +the Free Software Foundation. If the Library does not specify a +license version number, you may choose any version ever published by +the Free Software Foundation. + + 14. If you wish to incorporate parts of the Library into other free +programs whose distribution conditions are incompatible with these, +write to the author to ask for permission. For software which is +copyrighted by the Free Software Foundation, write to the Free +Software Foundation; we sometimes make exceptions for this. Our +decision will be guided by the two goals of preserving the free status +of all derivatives of our free software and of promoting the sharing +and reuse of software generally. + + NO WARRANTY + + 15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO +WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW. +EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR +OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY +KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE +LIBRARY IS WITH YOU. SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME +THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN +WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY +AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU +FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR +CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE +LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING +RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A +FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF +SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH +DAMAGES. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Libraries + + If you develop a new library, and you want it to be of the greatest +possible use to the public, we recommend making it free software that +everyone can redistribute and change. You can do so by permitting +redistribution under these terms (or, alternatively, under the terms of the +ordinary General Public License). + + To apply these terms, attach the following notices to the library. It is +safest to attach them to the start of each source file to most effectively +convey the exclusion of warranty; and each file should have at least the +"copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +Also add information on how to contact you by electronic and paper mail. + +You should also get your employer (if you work as a programmer) or your +school, if any, to sign a "copyright disclaimer" for the library, if +necessary. Here is a sample; alter the names: + + Yoyodyne, Inc., hereby disclaims all copyright interest in the + library `Frob' (a library for tweaking knobs) written by James Random Hacker. + + , 1 April 1990 + Ty Coon, President of Vice + +That's all there is to it! + + diff --git a/thirdParty/qserialport/Doxyfile b/thirdParty/qserialport/Doxyfile new file mode 100644 index 0000000000000000000000000000000000000000..515246414c500868d42ffdffd23ca8620702883d --- /dev/null +++ b/thirdParty/qserialport/Doxyfile @@ -0,0 +1,1272 @@ +# Doxyfile 1.5.2 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project +# +# All text after a hash (#) is considered a comment and will be ignored +# The format is: +# TAG = value [value, ...] +# For lists items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (" ") + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file that +# follow. The default is UTF-8 which is also the encoding used for all text before +# the first occurrence of this tag. Doxygen uses libiconv (or the iconv built into +# libc) for the transcoding. See http://www.gnu.org/software/libiconv for the list of +# possible encodings. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded +# by quotes) that should identify the project. + +PROJECT_NAME = "Qt Serial Port Library" + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. +# This could be handy for archiving the generated documentation or +# if some version control system is used. + +PROJECT_NUMBER = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) +# base path where the generated documentation will be put. +# If a relative path is entered, it will be relative to the location +# where doxygen was started. If left blank the current directory will be used. + +OUTPUT_DIRECTORY = apidocs + +# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create +# 4096 sub-directories (in 2 levels) under the output directory of each output +# format and will distribute the generated files over these directories. +# Enabling this option can be useful when feeding doxygen a huge amount of +# source files, where putting all generated files in the same directory would +# otherwise cause performance problems for the file system. + +CREATE_SUBDIRS = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# The default language is English, other supported languages are: +# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, +# Croatian, Czech, Danish, Dutch, Finnish, French, German, Greek, Hungarian, +# Italian, Japanese, Japanese-en (Japanese with English messages), Korean, +# Korean-en, Lithuanian, Norwegian, Polish, Portuguese, Romanian, Russian, +# Serbian, Slovak, Slovene, Spanish, Swedish, and Ukrainian. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will +# include brief member descriptions after the members that are listed in +# the file and class documentation (similar to JavaDoc). +# Set to NO to disable this. + +BRIEF_MEMBER_DESC = NO + +# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend +# the brief description of a member or function before the detailed description. +# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator +# that is used to form the text in various listings. Each string +# in this list, if found as the leading text of the brief description, will be +# stripped from the text and the result after processing the whole list, is +# used as the annotated text. Otherwise, the brief description is used as-is. +# If left blank, the following values are used ("$name" is automatically +# replaced with the name of the entity): "The $name class" "The $name widget" +# "The $name file" "is" "provides" "specifies" "contains" +# "represents" "a" "an" "the" + +ABBREVIATE_BRIEF = + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# Doxygen will generate a detailed section even if there is only a brief +# description. + +ALWAYS_DETAILED_SEC = YES + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full +# path before files name in the file list and in the header files. If set +# to NO the shortest path that makes the file name unique will be used. + +FULL_PATH_NAMES = NO + +# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag +# can be used to strip a user-defined part of the path. Stripping is +# only done if one of the specified strings matches the left-hand part of +# the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the +# path to strip. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of +# the path mentioned in the documentation of a class, which tells +# the reader which header file to include in order to use a class. +# If left blank only the name of the header file containing the class +# definition is used. Otherwise one should specify the include paths that +# are normally passed to the compiler using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter +# (but less readable) file names. This can be useful is your file systems +# doesn't support long names like on DOS, Mac, or CD-ROM. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen +# will interpret the first line (until the first dot) of a JavaDoc-style +# comment as the brief description. If set to NO, the JavaDoc +# comments will behave just like the Qt-style comments (thus requiring an +# explicit @brief command for a brief description. + +JAVADOC_AUTOBRIEF = YES + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen +# treat a multi-line C++ special comment block (i.e. a block of //! or /// +# comments) as a brief description. This used to be the default behaviour. +# The new default is to treat a multi-line C++ comment block as a detailed +# description. Set this tag to YES if you prefer the old behaviour instead. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the DETAILS_AT_TOP tag is set to YES then Doxygen +# will output the detailed description near the top, like JavaDoc. +# If set to NO, the detailed description appears after the member +# documentation. + +DETAILS_AT_TOP = NO + +# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented +# member inherits the documentation from any documented member that it +# re-implements. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce +# a new page for each member. If set to NO, the documentation of a member will +# be part of the file/class/namespace that contains it. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. +# Doxygen uses this value to replace tabs by spaces in code fragments. + +TAB_SIZE = 8 + +# This tag can be used to specify a number of aliases that acts +# as commands in the documentation. An alias has the form "name=value". +# For example adding "sideeffect=\par Side Effects:\n" will allow you to +# put the command \sideeffect (or @sideeffect) in the documentation, which +# will result in a user-defined paragraph with heading "Side Effects:". +# You can put \n's in the value part of an alias to insert newlines. + +ALIASES = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C +# sources only. Doxygen will then generate output that is more tailored for C. +# For instance, some of the names that are used will be different. The list +# of all members will be omitted, etc. + +OPTIMIZE_OUTPUT_FOR_C = NO + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java +# sources only. Doxygen will then generate output that is more tailored for Java. +# For instance, namespaces will be presented as packages, qualified scopes +# will look different, etc. + +OPTIMIZE_OUTPUT_JAVA = NO + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want to +# include (a tag file for) the STL sources as input, then you should +# set this tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); v.s. +# func(std::string) {}). This also make the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. + +CPP_CLI_SUPPORT = NO + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES, then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. + +DISTRIBUTE_GROUP_DOC = NO + +# Set the SUBGROUPING tag to YES (the default) to allow class member groups of +# the same type (for instance a group of public functions) to be put as a +# subgroup of that type (e.g. under the Public Functions section). Set it to +# NO to prevent subgrouping. Alternatively, this can be done per class using +# the \nosubgrouping command. + +SUBGROUPING = YES + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# documentation are documented, even if no documentation was available. +# Private class members and static file members will be hidden unless +# the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES + +EXTRACT_ALL = NO + +# If the EXTRACT_PRIVATE tag is set to YES all private members of a class +# will be included in the documentation. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_STATIC tag is set to YES all static members of a file +# will be included in the documentation. + +EXTRACT_STATIC = NO + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) +# defined locally in source files will be included in the documentation. +# If set to NO only classes defined in header files are included. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. When set to YES local +# methods, which are defined in the implementation section but not in +# the interface are included in the documentation. +# If set to NO (the default) only methods in the interface are included. + +EXTRACT_LOCAL_METHODS = NO + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all +# undocumented members of documented classes, files or namespaces. +# If set to NO (the default) these members will be included in the +# various overviews, but no documentation section is generated. +# This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. +# If set to NO (the default) these classes will be included in the various +# overviews. This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all +# friend (class|struct|union) declarations. +# If set to NO (the default) these declarations will be included in the +# documentation. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any +# documentation blocks found inside the body of a function. +# If set to NO (the default) these blocks will be appended to the +# function's detailed documentation block. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation +# that is typed after a \internal command is included. If the tag is set +# to NO (the default) then the documentation will be excluded. +# Set it to YES to include the internal documentation. + +INTERNAL_DOCS = YES + +# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate +# file names in lower-case letters. If set to YES upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. + +CASE_SENSE_NAMES = YES + +# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen +# will show members with their full class and namespace scopes in the +# documentation. If set to YES the scope will be hidden. + +HIDE_SCOPE_NAMES = NO + +# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen +# will put a list of the files that are included by a file in the documentation +# of that file. + +SHOW_INCLUDE_FILES = YES + +# If the INLINE_INFO tag is set to YES (the default) then a tag [inline] +# is inserted in the documentation for inline members. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen +# will sort the (detailed) documentation of file and class members +# alphabetically by member name. If set to NO the members will appear in +# declaration order. + +SORT_MEMBER_DOCS = NO + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the +# brief documentation of file, namespace and class members alphabetically +# by member name. If set to NO (the default) the members will appear in +# declaration order. + +SORT_BRIEF_DOCS = YES + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be +# sorted by fully-qualified names, including namespaces. If set to +# NO (the default), the class list will be sorted only by class name, +# not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the +# alphabetical list. + +SORT_BY_SCOPE_NAME = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or +# disable (NO) the todo list. This list is created by putting \todo +# commands in the documentation. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or +# disable (NO) the test list. This list is created by putting \test +# commands in the documentation. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or +# disable (NO) the bug list. This list is created by putting \bug +# commands in the documentation. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or +# disable (NO) the deprecated list. This list is created by putting +# \deprecated commands in the documentation. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional +# documentation sections, marked by \if sectionname ... \endif. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines +# the initial value of a variable or define consists of for it to appear in +# the documentation. If the initializer consists of more lines than specified +# here it will be hidden. Use a value of 0 to hide initializers completely. +# The appearance of the initializer of individual variables and defines in the +# documentation can be controlled using \showinitializer or \hideinitializer +# command in the documentation regardless of this setting. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated +# at the bottom of the documentation of classes and structs. If set to YES the +# list will mention the files that were used to generate the documentation. + +SHOW_USED_FILES = YES + +# If the sources in your project are distributed over multiple directories +# then setting the SHOW_DIRECTORIES tag to YES will show the directory hierarchy +# in the documentation. The default is NO. + +SHOW_DIRECTORIES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from the +# version control system). Doxygen will invoke the program by executing (via +# popen()) the command , where is the value of +# the FILE_VERSION_FILTER tag, and is the name of an input file +# provided by doxygen. Whatever the program writes to standard output +# is used as the file version. See the manual for examples. + +FILE_VERSION_FILTER = + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated +# by doxygen. Possible values are YES and NO. If left blank NO is used. + +QUIET = YES + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated by doxygen. Possible values are YES and NO. If left blank +# NO is used. + +WARNINGS = YES + +# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings +# for undocumented members. If EXTRACT_ALL is set to YES then this flag will +# automatically be disabled. + +WARN_IF_UNDOCUMENTED = YES + +# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some +# parameters in a documented function, or documenting parameters that +# don't exist or using markup commands wrongly. + +WARN_IF_DOC_ERROR = YES + +# This WARN_NO_PARAMDOC option can be abled to get warnings for +# functions that are documented, but have no documentation for their parameters +# or return value. If set to NO (the default) doxygen will only warn about +# wrong or incomplete parameter documentation, but not about the absence of +# documentation. + +WARN_NO_PARAMDOC = YES + +# The WARN_FORMAT tag determines the format of the warning messages that +# doxygen can produce. The string should contain the $file, $line, and $text +# tags, which will be replaced by the file and line number from which the +# warning originated and the warning text. Optionally the format may contain +# $version, which will be replaced by the version of the file (if it could +# be obtained via FILE_VERSION_FILTER) + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning +# and error messages should be written. If left blank the output is written +# to stderr. + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag can be used to specify the files and/or directories that contain +# documented source files. You may enter file names like "myfile.cpp" or +# directories like "/usr/src/myproject". Separate the files or directories +# with spaces. + +INPUT = examples \ + . \ + include/QtSerialPort + +# This tag can be used to specify the character encoding of the source files that +# doxygen parses. Internally doxygen uses the UTF-8 encoding, which is also the default +# input encoding. Doxygen uses libiconv (or the iconv built into libc) for the transcoding. +# See http://www.gnu.org/software/libiconv for the list of possible encodings. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank the following patterns are tested: +# *.c *.cc *.cxx *.cpp *.c++ *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh *.hxx +# *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.py + +FILE_PATTERNS = *.h \ + *.doco \ + Mainpage.dox + +# The RECURSIVE tag can be used to turn specify whether or not subdirectories +# should be searched for input files as well. Possible values are YES and NO. +# If left blank NO is used. + +RECURSIVE = NO + +# The EXCLUDE tag can be used to specify files and/or directories that should +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. + +EXCLUDE = + +# The EXCLUDE_SYMLINKS tag can be used select whether or not files or +# directories that are symbolic links (a Unix filesystem feature) are excluded +# from the input. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. Note that the wildcards are matched +# against the file with absolute path, so to exclude all test directories +# for example use the pattern */test/* + +EXCLUDE_PATTERNS = *.moc.* \ + moc* \ + *.all_cpp.* \ + *unload.* \ + */test/* \ + */tests/* + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the output. +# The symbol name can be a fully qualified name, a word, or if the wildcard * is used, +# a substring. Examples: ANamespace, AClass, AClass::ANamespace, ANamespace::*Test + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or +# directories that contain example code fragments that are included (see +# the \include command). + +EXAMPLE_PATH = examples/tranceiver \ + examples/serial2udpbridge + + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank all files are included. + +EXAMPLE_PATTERNS = + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude +# commands irrespective of the value of the RECURSIVE tag. +# Possible values are YES and NO. If left blank NO is used. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or +# directories that contain image that are included in the documentation (see +# the \image command). + +IMAGE_PATH = images + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command , where +# is the value of the INPUT_FILTER tag, and is the name of an +# input file. Doxygen will then use the output that the filter program writes +# to standard output. If FILTER_PATTERNS is specified, this tag will be +# ignored. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. The filters are a list of the form: +# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further +# info on how filters are used. If FILTER_PATTERNS is empty, INPUT_FILTER +# is applied to all files. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will be used to filter the input files when producing source +# files to browse (i.e. when SOURCE_BROWSER is set to YES). + +FILTER_SOURCE_FILES = NO + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will +# be generated. Documented entities will be cross-referenced with these sources. +# Note: To get rid of all source code in the generated output, make sure also +# VERBATIM_HEADERS is set to NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body +# of functions and classes directly in the documentation. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct +# doxygen to hide any special comment blocks from generated source code +# fragments. Normal C and C++ comments will always remain visible. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES (the default) +# then for each documented function all documented +# functions referencing it will be listed. + +REFERENCED_BY_RELATION = YES + +# If the REFERENCES_RELATION tag is set to YES (the default) +# then for each documented function all documented entities +# called/used by that function will be listed. + +REFERENCES_RELATION = YES + +# If the REFERENCES_LINK_SOURCE tag is set to YES (the default) +# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from +# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will +# link to the source code. Otherwise they will link to the documentstion. + +REFERENCES_LINK_SOURCE = YES + +# If the USE_HTAGS tag is set to YES then the references to source code +# will point to the HTML generated by the htags(1) tool instead of doxygen +# built-in source browser. The htags tool is part of GNU's global source +# tagging system (see http://www.gnu.org/software/global/global.html). You +# will need version 4.8.6 or higher. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen +# will generate a verbatim copy of the header file for each class for +# which an include is specified. Set to NO to disable this. + +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index +# of all compounds will be generated. Enable this if the project +# contains a lot of classes, structs, unions or interfaces. + +ALPHABETICAL_INDEX = NO + +# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then +# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns +# in which this list will be split (can be a number in the range [1..20]) + +COLS_IN_ALPHA_INDEX = 5 + +# In case all classes in a project start with a common prefix, all +# classes will be put under the same header in the alphabetical index. +# The IGNORE_PREFIX tag can be used to specify one or more prefixes that +# should be ignored while generating the index headers. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES (the default) Doxygen will +# generate HTML output. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `html' will be used as the default path. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for +# each generated HTML page (for example: .htm,.php,.asp). If it is left blank +# doxygen will generate files with .html extension. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a personal HTML header for +# each generated HTML page. If it is left blank doxygen will generate a +# standard header. + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a personal HTML footer for +# each generated HTML page. If it is left blank doxygen will generate a +# standard footer. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading +# style sheet that is used by each HTML page. It can be used to +# fine-tune the look of the HTML output. If the tag is left blank doxygen +# will generate a default style sheet. Note that doxygen will try to copy +# the style sheet file to the HTML output directory, so don't put your own +# stylesheet in the HTML output directory as well, or it will be erased! + +HTML_STYLESHEET = + +# If the HTML_ALIGN_MEMBERS tag is set to YES, the members of classes, +# files or namespaces will be aligned in HTML using tables. If set to +# NO a bullet list will be used. + +HTML_ALIGN_MEMBERS = YES + +# If the GENERATE_HTMLHELP tag is set to YES, additional index files +# will be generated that can be used as input for tools like the +# Microsoft HTML help workshop to generate a compressed HTML help file (.chm) +# of the generated HTML documentation. + +GENERATE_HTMLHELP = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can +# be used to specify the file name of the resulting .chm file. You +# can add a path in front of the file if the result should not be +# written to the html output directory. + +CHM_FILE = + +# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can +# be used to specify the location (absolute path including file name) of +# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run +# the HTML help compiler on the generated index.hhp. + +HHC_LOCATION = + +# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag +# controls if a separate .chi index file is generated (YES) or that +# it should be included in the master .chm file (NO). + +GENERATE_CHI = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag +# controls whether a binary table of contents is generated (YES) or a +# normal table of contents (NO) in the .chm file. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members +# to the contents of the HTML help documentation and to the tree view. + +TOC_EXPAND = NO + +# The DISABLE_INDEX tag can be used to turn on/off the condensed index at +# top of each HTML page. The value NO (the default) enables the index and +# the value YES disables it. + +DISABLE_INDEX = NO + +# This tag can be used to set the number of enum values (range [1..20]) +# that doxygen will group on one line in the generated HTML documentation. + +ENUM_VALUES_PER_LINE = 4 + +# If the GENERATE_TREEVIEW tag is set to YES, a side panel will be +# generated containing a tree-like index structure (just like the one that +# is generated for HTML Help). For this to work a browser that supports +# JavaScript, DHTML, CSS and frames is required (for instance Mozilla 1.0+, +# Netscape 6.0+, Internet explorer 5.0+, or Konqueror). Windows users are +# probably better off using the HTML help feature. + +GENERATE_TREEVIEW = NO + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be +# used to set the initial width (in pixels) of the frame in which the tree +# is shown. + +TREEVIEW_WIDTH = 250 + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will +# generate Latex output. + +GENERATE_LATEX = NO + +# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `latex' will be used as the default path. + +LATEX_OUTPUT = latex + +# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be +# invoked. If left blank `latex' will be used as the default command name. + +LATEX_CMD_NAME = latex + +# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to +# generate index for LaTeX. If left blank `makeindex' will be used as the +# default command name. + +MAKEINDEX_CMD_NAME = makeindex + +# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact +# LaTeX documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_LATEX = NO + +# The PAPER_TYPE tag can be used to set the paper type that is used +# by the printer. Possible values are: a4, a4wide, letter, legal and +# executive. If left blank a4wide will be used. + +PAPER_TYPE = a4wide + +# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX +# packages that should be included in the LaTeX output. + +EXTRA_PACKAGES = + +# The LATEX_HEADER tag can be used to specify a personal LaTeX header for +# the generated latex document. The header should contain everything until +# the first chapter. If it is left blank doxygen will generate a +# standard header. Notice: only use this tag if you know what you are doing! + +LATEX_HEADER = + +# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated +# is prepared for conversion to pdf (using ps2pdf). The pdf file will +# contain links (just like the HTML output) instead of page references +# This makes the output suitable for online browsing using a pdf viewer. + +PDF_HYPERLINKS = YES + +# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of +# plain latex in the generated Makefile. Set this option to YES to get a +# higher quality PDF documentation. + +USE_PDFLATEX = YES + +# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. +# command to the generated LaTeX files. This will instruct LaTeX to keep +# running if errors occur, instead of asking the user for help. +# This option is also used when generating formulas in HTML. + +LATEX_BATCHMODE = YES + +# If LATEX_HIDE_INDICES is set to YES then doxygen will not +# include the index chapters (such as File Index, Compound Index, etc.) +# in the output. + +LATEX_HIDE_INDICES = NO + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- + +# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output +# The RTF output is optimized for Word 97 and may not look very pretty with +# other RTF readers or editors. + +GENERATE_RTF = NO + +# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `rtf' will be used as the default path. + +RTF_OUTPUT = rtf + +# If the COMPACT_RTF tag is set to YES Doxygen generates more compact +# RTF documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_RTF = NO + +# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated +# will contain hyperlink fields. The RTF file will +# contain links (just like the HTML output) instead of page references. +# This makes the output suitable for online browsing using WORD or other +# programs which support those fields. +# Note: wordpad (write) and others do not support links. + +RTF_HYPERLINKS = NO + +# Load stylesheet definitions from file. Syntax is similar to doxygen's +# config file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. + +RTF_STYLESHEET_FILE = + +# Set optional variables used in the generation of an rtf document. +# Syntax is similar to doxygen's config file. + +RTF_EXTENSIONS_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- + +# If the GENERATE_MAN tag is set to YES (the default) Doxygen will +# generate man pages + +GENERATE_MAN = NO + +# The MAN_OUTPUT tag is used to specify where the man pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `man' will be used as the default path. + +MAN_OUTPUT = man + +# The MAN_EXTENSION tag determines the extension that is added to +# the generated man pages (default is the subroutine's section .3) + +MAN_EXTENSION = .3 + +# If the MAN_LINKS tag is set to YES and Doxygen generates man output, +# then it will generate one additional man file for each entity +# documented in the real man page(s). These additional files +# only source the real man page, but without them the man command +# would be unable to find the correct page. The default is NO. + +MAN_LINKS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- + +# If the GENERATE_XML tag is set to YES Doxygen will +# generate an XML file that captures the structure of +# the code including all documentation. + +GENERATE_XML = NO + +# The XML_OUTPUT tag is used to specify where the XML pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `xml' will be used as the default path. + +XML_OUTPUT = xml + +# The XML_SCHEMA tag can be used to specify an XML schema, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_SCHEMA = + +# The XML_DTD tag can be used to specify an XML DTD, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_DTD = + +# If the XML_PROGRAMLISTING tag is set to YES Doxygen will +# dump the program listings (including syntax highlighting +# and cross-referencing information) to the XML output. Note that +# enabling this will significantly increase the size of the XML output. + +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will +# generate an AutoGen Definitions (see autogen.sf.net) file +# that captures the structure of the code including all +# documentation. Note that this feature is still experimental +# and incomplete at the moment. + +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- + +# If the GENERATE_PERLMOD tag is set to YES Doxygen will +# generate a Perl module file that captures the structure of +# the code including all documentation. Note that this +# feature is still experimental and incomplete at the +# moment. + +GENERATE_PERLMOD = NO + +# If the PERLMOD_LATEX tag is set to YES Doxygen will generate +# the necessary Makefile rules, Perl scripts and LaTeX code to be able +# to generate PDF and DVI output from the Perl module output. + +PERLMOD_LATEX = NO + +# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be +# nicely formatted so it can be parsed by a human reader. This is useful +# if you want to understand what is going on. On the other hand, if this +# tag is set to NO the size of the Perl module output will be much smaller +# and Perl will parse it just the same. + +PERLMOD_PRETTY = YES + +# The names of the make variables in the generated doxyrules.make file +# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. +# This is useful so different doxyrules.make files included by the same +# Makefile don't overwrite each other's variables. + +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will +# evaluate all C-preprocessor directives found in the sources and include +# files. + +ENABLE_PREPROCESSING = YES + +# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro +# names in the source code. If set to NO (the default) only conditional +# compilation will be performed. Macro expansion can be done in a controlled +# way by setting EXPAND_ONLY_PREDEF to YES. + +MACRO_EXPANSION = NO + +# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES +# then the macro expansion is limited to the macros specified with the +# PREDEFINED and EXPAND_AS_DEFINED tags. + +EXPAND_ONLY_PREDEF = NO + +# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files +# in the INCLUDE_PATH (see below) will be search if a #include is found. + +SEARCH_INCLUDES = YES + +# The INCLUDE_PATH tag can be used to specify one or more directories that +# contain include files that are not input files but should be processed by +# the preprocessor. + +INCLUDE_PATH = + +# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard +# patterns (like *.h and *.hpp) to filter out the header-files in the +# directories. If left blank, the patterns specified with FILE_PATTERNS will +# be used. + +INCLUDE_FILE_PATTERNS = + +# The PREDEFINED tag can be used to specify one or more macro names that +# are defined before the preprocessor is started (similar to the -D option of +# gcc). The argument of the tag is a list of macros of the form: name +# or name=definition (no spaces). If the definition and the = are +# omitted =1 is assumed. To prevent a macro definition from being +# undefined via #undef or recursively expanded use the := operator +# instead of the = operator. + +# add DOXYGEN_NO_PROVIDER_API here to disable generation of the +# Provider API documentation with Doxygen. +PREDEFINED = DOXYGEN_SHOULD_SKIP_THIS \ + QPIPE_SECURE + + +# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then +# this tag can be used to specify a list of macro names that should be expanded. +# The macro definition that is found in the sources will be used. +# Use the PREDEFINED tag if you want to use a different macro definition. + +EXPAND_AS_DEFINED = TNX_EXPORT + +# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then +# doxygen's preprocessor will remove all function-like macros that are alone +# on a line, have an all uppercase name, and do not end with a semicolon. Such +# function macros are typically used for boiler-plate code, and will confuse +# the parser if not removed. + +SKIP_FUNCTION_MACROS = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to external references +#--------------------------------------------------------------------------- + +# The TAGFILES option can be used to specify one or more tagfiles. +# Optionally an initial location of the external documentation +# can be added for each tagfile. The format of a tag file without +# this location is as follows: +# TAGFILES = file1 file2 ... +# Adding location for the tag files is done as follows: +# TAGFILES = file1=loc1 "file2 = loc2" ... +# where "loc1" and "loc2" can be relative or absolute paths or +# URLs. If a location is present for each tag, the installdox tool +# does not have to be run to correct the links. +# Note that each tag file must have a unique name +# (where the name does NOT include the path) +# If a tag file is not located in the directory in which doxygen +# is run, you must also specify the path to the tagfile here. + +TAGFILES = src/qt.tag + +# When a file name is specified after GENERATE_TAGFILE, doxygen will create +# a tag file that is based on the input files it reads. + +GENERATE_TAGFILE = + +# If the ALLEXTERNALS tag is set to YES all external classes will be listed +# in the class index. If set to NO only the inherited external classes +# will be listed. + +ALLEXTERNALS = NO + +# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed +# in the modules index. If set to NO, only the current project's groups will +# be listed. + +EXTERNAL_GROUPS = YES + +# The PERL_PATH should be the absolute path and name of the perl script +# interpreter (i.e. the result of `which perl'). + +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will +# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base +# or super classes. Setting the tag to NO turns the diagrams off. Note that +# this option is superseded by the HAVE_DOT option below. This is only a +# fallback. It is recommended to install and use dot, since it yields more +# powerful graphs. + +CLASS_DIAGRAMS = YES + +# You can define message sequence charts within doxygen comments using the \msc +# command. Doxygen will then run the mscgen tool (see http://www.mcternan.me.uk/mscgen/) to +# produce the chart and insert it in the documentation. The MSCGEN_PATH tag allows you to +# specify the directory where the mscgen tool resides. If left empty the tool is assumed to +# be found in the default search path. + +MSCGEN_PATH = + +# If set to YES, the inheritance and collaboration graphs will hide +# inheritance and usage relations if the target is undocumented +# or is not a class. + +HIDE_UNDOC_RELATIONS = NO + +# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is +# available from the path. This tool is part of Graphviz, a graph visualization +# toolkit from AT&T and Lucent Bell Labs. The other options in this section +# have no effect if this option is set to NO (the default) + +HAVE_DOT = YES + +# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect inheritance relations. Setting this tag to YES will force the +# the CLASS_DIAGRAMS tag to NO. + +CLASS_GRAPH = NO + +# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect implementation dependencies (inheritance, containment, and +# class references variables) of the class with other documented classes. + +COLLABORATION_GRAPH = YES + +# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for groups, showing the direct groups dependencies + +GROUP_GRAPHS = YES + +# If the UML_LOOK tag is set to YES doxygen will generate inheritance and +# collaboration diagrams in a style similar to the OMG's Unified Modeling +# Language. + +UML_LOOK = NO + +# If set to YES, the inheritance and collaboration graphs will show the +# relations between templates and their instances. + +TEMPLATE_RELATIONS = NO + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT +# tags are set to YES then doxygen will generate a graph for each documented +# file showing the direct and indirect include dependencies of the file with +# other documented files. + +INCLUDE_GRAPH = YES + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and +# HAVE_DOT tags are set to YES then doxygen will generate a graph for each +# documented header file showing the documented files that directly or +# indirectly include this file. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH and HAVE_DOT tags are set to YES then doxygen will +# generate a call dependency graph for every global function or class method. +# Note that enabling this option will significantly increase the time of a run. +# So in most cases it will be better to enable call graphs for selected +# functions only using the \callgraph command. + +CALL_GRAPH = NO + +# If the CALLER_GRAPH and HAVE_DOT tags are set to YES then doxygen will +# generate a caller dependency graph for every global function or class method. +# Note that enabling this option will significantly increase the time of a run. +# So in most cases it will be better to enable caller graphs for selected +# functions only using the \callergraph command. + +CALLER_GRAPH = NO + +# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen +# will graphical hierarchy of all classes instead of a textual one. + +GRAPHICAL_HIERARCHY = YES + +# If the DIRECTORY_GRAPH, SHOW_DIRECTORIES and HAVE_DOT tags are set to YES +# then doxygen will show the dependencies a directory has on other directories +# in a graphical way. The dependency relations are determined by the #include +# relations between the files in the directories. + +DIRECTORY_GRAPH = YES + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. Possible values are png, jpg, or gif +# If left blank png will be used. + +DOT_IMAGE_FORMAT = png + +# The tag DOT_PATH can be used to specify the path where the dot tool can be +# found. If left blank, it is assumed the dot tool can be found in the path. + +DOT_PATH = + +# The DOTFILE_DIRS tag can be used to specify one or more directories that +# contain dot files that are included in the documentation (see the +# \dotfile command). + +DOTFILE_DIRS = + +# The MAX_DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of +# nodes that will be shown in the graph. If the number of nodes in a graph +# becomes larger than this value, doxygen will truncate the graph, which is +# visualized by representing a node as a red box. Note that doxygen will always +# show the root nodes and its direct children regardless of this setting. + +DOT_GRAPH_MAX_NODES = 50 + +# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent +# background. This is disabled by default, which results in a white background. +# Warning: Depending on the platform used, enabling this option may lead to +# badly anti-aliased labels on the edges of a graph (i.e. they become hard to +# read). + +DOT_TRANSPARENT = NO + +# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output +# files in one run (i.e. multiple -o and -T options on the command line). This +# makes dot run faster, but since only newer versions of dot (>1.8.10) +# support this, this feature is disabled by default. + +DOT_MULTI_TARGETS = NO + +# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will +# generate a legend page explaining the meaning of the various boxes and +# arrows in the dot generated graphs. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will +# remove the intermediate dot files that are used to generate +# the various graphs. + +DOT_CLEANUP = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to the search engine +#--------------------------------------------------------------------------- + +# The SEARCHENGINE tag specifies whether or not a search engine should be +# used. If set to NO the values of all tags below this one will be ignored. + +SEARCHENGINE = NO diff --git a/thirdParty/qserialport/INSTALL b/thirdParty/qserialport/INSTALL new file mode 100644 index 0000000000000000000000000000000000000000..b10227a6d37568c03302355546e2e7558f056d2d --- /dev/null +++ b/thirdParty/qserialport/INSTALL @@ -0,0 +1,46 @@ +Installing QSerialPort +---------------------- + +QSerialPort requires Qt 4.6 or greater. + +For Mac/Unix/Linux/Embedded Linux: + + ./configure + make + make install + /sbin/ldconfig, if necessary + +For Windows: + + configure + nmake (or make) + installwin + +For Wince: + qmake -r qserialport.pro -spec + nmake + + i.e "qmake -r qserialport.pro -spec wince50standard-x86-msvc2005" for wince 5.0 standard sdk + + +Notes +----- + - On unix, use --prefix=$PWD to build in-place + + - if 'configure' doesn't work on Mac OSX (it doesn't work if QT is installed as SDK), use the following instead: + qmake -r qserialport.pro -spec macx-g++ + make + make install + + Optionally add lib_bundle config value to build it as framework: + qmake -r qserialport.pro -spec macx-g++ CONFIG+=lib_bundle + + - To build QSerialPort as static library try CONFIG+=static with qmake or add it into conf.pri file. + + - Visual Studio 2005 solution and project files are included into the package. Current solution is prepared for WIN32 builds. + If you want to build QSerialPort for WINCE using Visual Studio then do the following: + o replace qserialportnative_win32.cpp with qserialportnative_wince.cpp + o add wincommevtbreaker.cpp and wincommevtbreaker.h files into the project + +Please report problems to: + labs@inbiza.com diff --git a/thirdParty/qserialport/LICENSE b/thirdParty/qserialport/LICENSE new file mode 100644 index 0000000000000000000000000000000000000000..aab009acaf07b65408f1507cecaa9e4c6bb3c8e9 --- /dev/null +++ b/thirdParty/qserialport/LICENSE @@ -0,0 +1,509 @@ +Copyright (c) 2010, Inbiza Systems Inc. All rights reserved. + +This software is distributed under the terms of the GNU Lesser General Public License version 2.1. For other licensing options please contact Inbza systems http://www.inbiza.com/contact-us.html. + + + GNU LESSER GENERAL PUBLIC LICENSE + Version 2.1, February 1999 + + Copyright (C) 1991, 1999 Free Software Foundation, Inc. + 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + +[This is the first released version of the Lesser GPL. It also counts + as the successor of the GNU Library Public License, version 2, hence + the version number 2.1.] + + Preamble + + The licenses for most software are designed to take away your +freedom to share and change it. By contrast, the GNU General Public +Licenses are intended to guarantee your freedom to share and change +free software--to make sure the software is free for all its users. + + This license, the Lesser General Public License, applies to some +specially designated software packages--typically libraries--of the +Free Software Foundation and other authors who decide to use it. You +can use it too, but we suggest you first think carefully about whether +this license or the ordinary General Public License is the better +strategy to use in any particular case, based on the explanations below. + + When we speak of free software, we are referring to freedom of use, +not price. Our General Public Licenses are designed to make sure that +you have the freedom to distribute copies of free software (and charge +for this service if you wish); that you receive source code or can get +it if you want it; that you can change the software and use pieces of +it in new free programs; and that you are informed that you can do +these things. + + To protect your rights, we need to make restrictions that forbid +distributors to deny you these rights or to ask you to surrender these +rights. These restrictions translate to certain responsibilities for +you if you distribute copies of the library or if you modify it. + + For example, if you distribute copies of the library, whether gratis +or for a fee, you must give the recipients all the rights that we gave +you. You must make sure that they, too, receive or can get the source +code. If you link other code with the library, you must provide +complete object files to the recipients, so that they can relink them +with the library after making changes to the library and recompiling +it. And you must show them these terms so they know their rights. + + We protect your rights with a two-step method: (1) we copyright the +library, and (2) we offer you this license, which gives you legal +permission to copy, distribute and/or modify the library. + + To protect each distributor, we want to make it very clear that +there is no warranty for the free library. Also, if the library is +modified by someone else and passed on, the recipients should know +that what they have is not the original version, so that the original +author's reputation will not be affected by problems that might be +introduced by others. + + Finally, software patents pose a constant threat to the existence of +any free program. We wish to make sure that a company cannot +effectively restrict the users of a free program by obtaining a +restrictive license from a patent holder. Therefore, we insist that +any patent license obtained for a version of the library must be +consistent with the full freedom of use specified in this license. + + Most GNU software, including some libraries, is covered by the +ordinary GNU General Public License. This license, the GNU Lesser +General Public License, applies to certain designated libraries, and +is quite different from the ordinary General Public License. We use +this license for certain libraries in order to permit linking those +libraries into non-free programs. + + When a program is linked with a library, whether statically or using +a shared library, the combination of the two is legally speaking a +combined work, a derivative of the original library. The ordinary +General Public License therefore permits such linking only if the +entire combination fits its criteria of freedom. The Lesser General +Public License permits more lax criteria for linking other code with +the library. + + We call this license the "Lesser" General Public License because it +does Less to protect the user's freedom than the ordinary General +Public License. It also provides other free software developers Less +of an advantage over competing non-free programs. These disadvantages +are the reason we use the ordinary General Public License for many +libraries. However, the Lesser license provides advantages in certain +special circumstances. + + For example, on rare occasions, there may be a special need to +encourage the widest possible use of a certain library, so that it becomes +a de-facto standard. To achieve this, non-free programs must be +allowed to use the library. A more frequent case is that a free +library does the same job as widely used non-free libraries. In this +case, there is little to gain by limiting the free library to free +software only, so we use the Lesser General Public License. + + In other cases, permission to use a particular library in non-free +programs enables a greater number of people to use a large body of +free software. For example, permission to use the GNU C Library in +non-free programs enables many more people to use the whole GNU +operating system, as well as its variant, the GNU/Linux operating +system. + + Although the Lesser General Public License is Less protective of the +users' freedom, it does ensure that the user of a program that is +linked with the Library has the freedom and the wherewithal to run +that program using a modified version of the Library. + + The precise terms and conditions for copying, distribution and +modification follow. Pay close attention to the difference between a +"work based on the library" and a "work that uses the library". The +former contains code derived from the library, whereas the latter must +be combined with the library in order to run. + + GNU LESSER GENERAL PUBLIC LICENSE + TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION + + 0. This License Agreement applies to any software library or other +program which contains a notice placed by the copyright holder or +other authorized party saying it may be distributed under the terms of +this Lesser General Public License (also called "this License"). +Each licensee is addressed as "you". + + A "library" means a collection of software functions and/or data +prepared so as to be conveniently linked with application programs +(which use some of those functions and data) to form executables. + + The "Library", below, refers to any such software library or work +which has been distributed under these terms. A "work based on the +Library" means either the Library or any derivative work under +copyright law: that is to say, a work containing the Library or a +portion of it, either verbatim or with modifications and/or translated +straightforwardly into another language. (Hereinafter, translation is +included without limitation in the term "modification".) + + "Source code" for a work means the preferred form of the work for +making modifications to it. For a library, complete source code means +all the source code for all modules it contains, plus any associated +interface definition files, plus the scripts used to control compilation +and installation of the library. + + Activities other than copying, distribution and modification are not +covered by this License; they are outside its scope. The act of +running a program using the Library is not restricted, and output from +such a program is covered only if its contents constitute a work based +on the Library (independent of the use of the Library in a tool for +writing it). Whether that is true depends on what the Library does +and what the program that uses the Library does. + + 1. You may copy and distribute verbatim copies of the Library's +complete source code as you receive it, in any medium, provided that +you conspicuously and appropriately publish on each copy an +appropriate copyright notice and disclaimer of warranty; keep intact +all the notices that refer to this License and to the absence of any +warranty; and distribute a copy of this License along with the +Library. + + You may charge a fee for the physical act of transferring a copy, +and you may at your option offer warranty protection in exchange for a +fee. + + 2. You may modify your copy or copies of the Library or any portion +of it, thus forming a work based on the Library, and copy and +distribute such modifications or work under the terms of Section 1 +above, provided that you also meet all of these conditions: + + a) The modified work must itself be a software library. + + b) You must cause the files modified to carry prominent notices + stating that you changed the files and the date of any change. + + c) You must cause the whole of the work to be licensed at no + charge to all third parties under the terms of this License. + + d) If a facility in the modified Library refers to a function or a + table of data to be supplied by an application program that uses + the facility, other than as an argument passed when the facility + is invoked, then you must make a good faith effort to ensure that, + in the event an application does not supply such function or + table, the facility still operates, and performs whatever part of + its purpose remains meaningful. + + (For example, a function in a library to compute square roots has + a purpose that is entirely well-defined independent of the + application. Therefore, Subsection 2d requires that any + application-supplied function or table used by this function must + be optional: if the application does not supply it, the square + root function must still compute square roots.) + +These requirements apply to the modified work as a whole. If +identifiable sections of that work are not derived from the Library, +and can be reasonably considered independent and separate works in +themselves, then this License, and its terms, do not apply to those +sections when you distribute them as separate works. But when you +distribute the same sections as part of a whole which is a work based +on the Library, the distribution of the whole must be on the terms of +this License, whose permissions for other licensees extend to the +entire whole, and thus to each and every part regardless of who wrote +it. + +Thus, it is not the intent of this section to claim rights or contest +your rights to work written entirely by you; rather, the intent is to +exercise the right to control the distribution of derivative or +collective works based on the Library. + +In addition, mere aggregation of another work not based on the Library +with the Library (or with a work based on the Library) on a volume of +a storage or distribution medium does not bring the other work under +the scope of this License. + + 3. You may opt to apply the terms of the ordinary GNU General Public +License instead of this License to a given copy of the Library. To do +this, you must alter all the notices that refer to this License, so +that they refer to the ordinary GNU General Public License, version 2, +instead of to this License. (If a newer version than version 2 of the +ordinary GNU General Public License has appeared, then you can specify +that version instead if you wish.) Do not make any other change in +these notices. + + Once this change is made in a given copy, it is irreversible for +that copy, so the ordinary GNU General Public License applies to all +subsequent copies and derivative works made from that copy. + + This option is useful when you wish to copy part of the code of +the Library into a program that is not a library. + + 4. You may copy and distribute the Library (or a portion or +derivative of it, under Section 2) in object code or executable form +under the terms of Sections 1 and 2 above provided that you accompany +it with the complete corresponding machine-readable source code, which +must be distributed under the terms of Sections 1 and 2 above on a +medium customarily used for software interchange. + + If distribution of object code is made by offering access to copy +from a designated place, then offering equivalent access to copy the +source code from the same place satisfies the requirement to +distribute the source code, even though third parties are not +compelled to copy the source along with the object code. + + 5. A program that contains no derivative of any portion of the +Library, but is designed to work with the Library by being compiled or +linked with it, is called a "work that uses the Library". Such a +work, in isolation, is not a derivative work of the Library, and +therefore falls outside the scope of this License. + + However, linking a "work that uses the Library" with the Library +creates an executable that is a derivative of the Library (because it +contains portions of the Library), rather than a "work that uses the +library". The executable is therefore covered by this License. +Section 6 states terms for distribution of such executables. + + When a "work that uses the Library" uses material from a header file +that is part of the Library, the object code for the work may be a +derivative work of the Library even though the source code is not. +Whether this is true is especially significant if the work can be +linked without the Library, or if the work is itself a library. The +threshold for this to be true is not precisely defined by law. + + If such an object file uses only numerical parameters, data +structure layouts and accessors, and small macros and small inline +functions (ten lines or less in length), then the use of the object +file is unrestricted, regardless of whether it is legally a derivative +work. (Executables containing this object code plus portions of the +Library will still fall under Section 6.) + + Otherwise, if the work is a derivative of the Library, you may +distribute the object code for the work under the terms of Section 6. +Any executables containing that work also fall under Section 6, +whether or not they are linked directly with the Library itself. + + 6. As an exception to the Sections above, you may also combine or +link a "work that uses the Library" with the Library to produce a +work containing portions of the Library, and distribute that work +under terms of your choice, provided that the terms permit +modification of the work for the customer's own use and reverse +engineering for debugging such modifications. + + You must give prominent notice with each copy of the work that the +Library is used in it and that the Library and its use are covered by +this License. You must supply a copy of this License. If the work +during execution displays copyright notices, you must include the +copyright notice for the Library among them, as well as a reference +directing the user to the copy of this License. Also, you must do one +of these things: + + a) Accompany the work with the complete corresponding + machine-readable source code for the Library including whatever + changes were used in the work (which must be distributed under + Sections 1 and 2 above); and, if the work is an executable linked + with the Library, with the complete machine-readable "work that + uses the Library", as object code and/or source code, so that the + user can modify the Library and then relink to produce a modified + executable containing the modified Library. (It is understood + that the user who changes the contents of definitions files in the + Library will not necessarily be able to recompile the application + to use the modified definitions.) + + b) Use a suitable shared library mechanism for linking with the + Library. A suitable mechanism is one that (1) uses at run time a + copy of the library already present on the user's computer system, + rather than copying library functions into the executable, and (2) + will operate properly with a modified version of the library, if + the user installs one, as long as the modified version is + interface-compatible with the version that the work was made with. + + c) Accompany the work with a written offer, valid for at + least three years, to give the same user the materials + specified in Subsection 6a, above, for a charge no more + than the cost of performing this distribution. + + d) If distribution of the work is made by offering access to copy + from a designated place, offer equivalent access to copy the above + specified materials from the same place. + + e) Verify that the user has already received a copy of these + materials or that you have already sent this user a copy. + + For an executable, the required form of the "work that uses the +Library" must include any data and utility programs needed for +reproducing the executable from it. However, as a special exception, +the materials to be distributed need not include anything that is +normally distributed (in either source or binary form) with the major +components (compiler, kernel, and so on) of the operating system on +which the executable runs, unless that component itself accompanies +the executable. + + It may happen that this requirement contradicts the license +restrictions of other proprietary libraries that do not normally +accompany the operating system. Such a contradiction means you cannot +use both them and the Library together in an executable that you +distribute. + + 7. You may place library facilities that are a work based on the +Library side-by-side in a single library together with other library +facilities not covered by this License, and distribute such a combined +library, provided that the separate distribution of the work based on +the Library and of the other library facilities is otherwise +permitted, and provided that you do these two things: + + a) Accompany the combined library with a copy of the same work + based on the Library, uncombined with any other library + facilities. This must be distributed under the terms of the + Sections above. + + b) Give prominent notice with the combined library of the fact + that part of it is a work based on the Library, and explaining + where to find the accompanying uncombined form of the same work. + + 8. You may not copy, modify, sublicense, link with, or distribute +the Library except as expressly provided under this License. Any +attempt otherwise to copy, modify, sublicense, link with, or +distribute the Library is void, and will automatically terminate your +rights under this License. However, parties who have received copies, +or rights, from you under this License will not have their licenses +terminated so long as such parties remain in full compliance. + + 9. You are not required to accept this License, since you have not +signed it. However, nothing else grants you permission to modify or +distribute the Library or its derivative works. These actions are +prohibited by law if you do not accept this License. Therefore, by +modifying or distributing the Library (or any work based on the +Library), you indicate your acceptance of this License to do so, and +all its terms and conditions for copying, distributing or modifying +the Library or works based on it. + + 10. Each time you redistribute the Library (or any work based on the +Library), the recipient automatically receives a license from the +original licensor to copy, distribute, link with or modify the Library +subject to these terms and conditions. You may not impose any further +restrictions on the recipients' exercise of the rights granted herein. +You are not responsible for enforcing compliance by third parties with +this License. + + 11. If, as a consequence of a court judgment or allegation of patent +infringement or for any other reason (not limited to patent issues), +conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot +distribute so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you +may not distribute the Library at all. For example, if a patent +license would not permit royalty-free redistribution of the Library by +all those who receive copies directly or indirectly through you, then +the only way you could satisfy both it and this License would be to +refrain entirely from distribution of the Library. + +If any portion of this section is held invalid or unenforceable under any +particular circumstance, the balance of the section is intended to apply, +and the section as a whole is intended to apply in other circumstances. + +It is not the purpose of this section to induce you to infringe any +patents or other property right claims or to contest validity of any +such claims; this section has the sole purpose of protecting the +integrity of the free software distribution system which is +implemented by public license practices. Many people have made +generous contributions to the wide range of software distributed +through that system in reliance on consistent application of that +system; it is up to the author/donor to decide if he or she is willing +to distribute software through any other system and a licensee cannot +impose that choice. + +This section is intended to make thoroughly clear what is believed to +be a consequence of the rest of this License. + + 12. If the distribution and/or use of the Library is restricted in +certain countries either by patents or by copyrighted interfaces, the +original copyright holder who places the Library under this License may add +an explicit geographical distribution limitation excluding those countries, +so that distribution is permitted only in or among countries not thus +excluded. In such case, this License incorporates the limitation as if +written in the body of this License. + + 13. The Free Software Foundation may publish revised and/or new +versions of the Lesser General Public License from time to time. +Such new versions will be similar in spirit to the present version, +but may differ in detail to address new problems or concerns. + +Each version is given a distinguishing version number. If the Library +specifies a version number of this License which applies to it and +"any later version", you have the option of following the terms and +conditions either of that version or of any later version published by +the Free Software Foundation. If the Library does not specify a +license version number, you may choose any version ever published by +the Free Software Foundation. + + 14. If you wish to incorporate parts of the Library into other free +programs whose distribution conditions are incompatible with these, +write to the author to ask for permission. For software which is +copyrighted by the Free Software Foundation, write to the Free +Software Foundation; we sometimes make exceptions for this. Our +decision will be guided by the two goals of preserving the free status +of all derivatives of our free software and of promoting the sharing +and reuse of software generally. + + NO WARRANTY + + 15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO +WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW. +EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR +OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY +KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE +LIBRARY IS WITH YOU. SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME +THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN +WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY +AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU +FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR +CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE +LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING +RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A +FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF +SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH +DAMAGES. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Libraries + + If you develop a new library, and you want it to be of the greatest +possible use to the public, we recommend making it free software that +everyone can redistribute and change. You can do so by permitting +redistribution under these terms (or, alternatively, under the terms of the +ordinary General Public License). + + To apply these terms, attach the following notices to the library. It is +safest to attach them to the start of each source file to most effectively +convey the exclusion of warranty; and each file should have at least the +"copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +Also add information on how to contact you by electronic and paper mail. + +You should also get your employer (if you work as a programmer) or your +school, if any, to sign a "copyright disclaimer" for the library, if +necessary. Here is a sample; alter the names: + + Yoyodyne, Inc., hereby disclaims all copyright interest in the + library `Frob' (a library for tweaking knobs) written by James Random Hacker. + + , 1 April 1990 + Ty Coon, President of Vice + +That's all there is to it! + + diff --git a/thirdParty/qserialport/Mainpage.dox b/thirdParty/qserialport/Mainpage.dox new file mode 100644 index 0000000000000000000000000000000000000000..af0cfbc26c9dc54809aa1690b5918d4da4bc67cd --- /dev/null +++ b/thirdParty/qserialport/Mainpage.dox @@ -0,0 +1,67 @@ +/** + \mainpage Unofficial Qt Serial Port Library + + %QSerialPort is a cross-platform serial port library, using Qt datatypes and + conventions. %QSerialPort inherits from QIODevice + and works natively with any Qt class that uses QIODevice objects as input or output. + + %QSerialPort should work everywhere %Qt does, including Windows/Unix/Linux/Embedded Linux/WinCE/MacOSX. This + version of %QSerialPort is for Qt4, and requires no Qt3 compatibility code. + + \section Characteristics Device Characteristics + + %QSerialPort has the following QIODevice characteristics: + - Supports event-driven and polling programming models + - It is a sequential device like QProcess and + QTcpSocket + - It is an unbuffered device + + \section using Using QSerialPort + + The application simply includes <QSerialPort> and links to + libqserialport. There are additional examples available in the "examples" directory. + + You will notice that %QSerialPort is part of TNX namespace. TNX stands for Tonix + which is a Qt based cross-platform hardware control framework with built in JavaScript support. Since Tonix + is specially designed for embedded system development and robotics projects %QSerialPort is an essential part of it. + + Example: + \code + #include + + int main(int argc, char *argv[]) + { + using namespace TNX; + + QCoreApplication a(argc, argv); + + QSerialPort serport("COM5", "9600,8,n,1"); + if ( !serport.open() ) + qFatal("Cannot open serial port %s. Exiting..", qPrintable(portName)); + + if ( !serport.setCommTimeouts(QSerialPort::CtScheme_NonBlockingRead) ) + qWarning("Cannot set communications timeout values at port %s.", qPrintable(portName)); + + int byteCounter = 0; + forever { + if ( serport.waitForReadyRead(5000) ) { // 5sec + QByteArray data = serport.read(512); + byteCounter += data.size(); + std::cout << "Received data @ " << qPrintable(QDateTime::currentDateTime().toString("hh:mm:ss.zzz")) << + ". Echo back." << std::endl; + serport.write(data); + if ( byteCounter >= 4096 ) + break; + } + else { + std::cout << "Timeout while waiting for incoming data @ " << + qPrintable(QDateTime::currentDateTime().toString("hh:mm:ss.zzz")) << std::endl; + } + } + + std::cout << "Polling example is terminated successfully." << std::endl; + return 0; + } + \endcode + +*/ diff --git a/thirdParty/qserialport/README b/thirdParty/qserialport/README new file mode 100644 index 0000000000000000000000000000000000000000..a1eaf48feeaef0103055c5658e1c8bac4c028dbc --- /dev/null +++ b/thirdParty/qserialport/README @@ -0,0 +1,37 @@ +Unofficial Qt Serial Port library version 1.0.0 alpha +----------------------------------------------------- +Date: October 15th, 2010 +Website: http://www.inbiza.com/labs + +Description +----------- + QSerialPort is a high performance cross platform serial library based on the QIODevice class from the Qt framework. Building this library on QIODevice allows for a much more integrated and native experience when developing Qt based applications. + + The project stems from our work on high performance embedded systems where we need to squeeze out as much IO performance as possible from hardware with limited resources. + + This library has been tested on: + Ð Linux on x86 and ARM ; + Ð Windows XP and CE 5 on x86; + Ð OS X 10.6 on x86 with a FTDI USB to Serial bridge. + + API Documentation is located in the 'apidocs' subdirectory. Run 'make doc' to generate the documentation on a Linux system with Doxygen installed. + +Special Thanks +-------------- + We used Qt Cryptographic Architecture (QCA) project's layout + and qmake configuration as a model for our project. We thank to + Justin Karneges and QCA team for their great work. + +Install +------- + For installation or compiling instructions, see the INSTALL file. + +License +------- + This software is distributed under the terms of the GNU Lesser General Public License version 2.1. + +Changes +------- + + + diff --git a/thirdParty/qserialport/TODO b/thirdParty/qserialport/TODO new file mode 100644 index 0000000000000000000000000000000000000000..b1c9df17e3fb67e52d31099c02f614a289d2dbb2 --- /dev/null +++ b/thirdParty/qserialport/TODO @@ -0,0 +1,11 @@ +* 1.0.0 Alpha + +o Symbian support +o mingw test/support +o Increase testing coverage - see TestPlan for details +o Make sure that QSerialPort works properly when created by a thread other than the main thread +o Add breakState() method +o Test line signal related methods +o Code cleanup +o Better documentation + diff --git a/thirdParty/qserialport/app.pri b/thirdParty/qserialport/app.pri new file mode 100644 index 0000000000000000000000000000000000000000..e12cbe730520593761f04e75de4b201d5faaf5df --- /dev/null +++ b/thirdParty/qserialport/app.pri @@ -0,0 +1,43 @@ +## +## Unofficial Qt Serial Port Library +## +## Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. +## +## This program is free software: you can redistribute it and/or modify it +## under the terms of the GNU Lesser General Public License as published by the +## Free Software Foundation, either version 3 of the License, or (at your +## option) any later version. +## +## This program is distributed in the hope that it will be useful, but WITHOUT +## ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or +## FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for +## more details. +## +## You should have received a copy of the GNU Lesser General Public License +## along with this program. If not, see +## +## +## @file app.pri +## www.inbiza.com +## + +include(confapp.pri) +include(base.pri) + +macx:QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6 #for universal + +# qmake configuring apps with staticlib poses linking problems + +windows|wince*:staticlib { + CONFIG-=shared + CONFIG-=staticlib + CONFIG+=static +} + +exists(qserialport.prf) { + # our apps should build against the qserialport in this tree + include(qserialport.prf) +} else { + # attempt to use system-wide qserialport + CONFIG *= qserialport +} diff --git a/thirdParty/qserialport/base.pri b/thirdParty/qserialport/base.pri new file mode 100644 index 0000000000000000000000000000000000000000..43f40042e378963cc13429fc503d8b2cc9b21706 --- /dev/null +++ b/thirdParty/qserialport/base.pri @@ -0,0 +1,40 @@ +## +## Unofficial Qt Serial Port Library +## +## Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. +## +## This program is free software: you can redistribute it and/or modify it +## under the terms of the GNU Lesser General Public License as published by the +## Free Software Foundation, either version 3 of the License, or (at your +## option) any later version. +## +## This program is distributed in the hope that it will be useful, but WITHOUT +## ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or +## FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for +## more details. +## +## You should have received a copy of the GNU Lesser General Public License +## along with this program. If not, see +## +## +## @file base.pri +## www.inbiza.com +## + +!isEmpty( QMAKESPEC ) { + MKSPEC = $$replace(QMAKESPEC,-," ") + MKSPEC = $$join(MKSPEC, " -L", ) + PLATFORM_NAME = $$member(MKSPEC) +} +else{ + unix:PLATFORM_NAME = $$system( uname -s ) + windows: PLATFORM_NAME = Win32 +} + +QSERIALPORT_BASE = $$PWD +QSERIALPORT_SRCBASE = $$QSERIALPORT_BASE/src +QSERIALPORT_INCBASE = $$QSERIALPORT_BASE/include +QSERIALPORT_LIBDIR = $$QSERIALPORT_BASE/lib +QSERIALPORT_BUILDDIR = $$QSERIALPORT_BASE/build/$$PLATFORM_NAME +QSERIALPORT_BINDESTDIR = $$QSERIALPORT_BASE/bin + diff --git a/thirdParty/qserialport/conf.pri b/thirdParty/qserialport/conf.pri new file mode 100644 index 0000000000000000000000000000000000000000..de7bcddd695867cfe95b5e8edf394954212ae946 --- /dev/null +++ b/thirdParty/qserialport/conf.pri @@ -0,0 +1,7 @@ +# qconf + +PREFIX = /usr/local +BINDIR = /usr/local/bin +DATADIR = /usr/local/share + + diff --git a/thirdParty/qserialport/confapp.pri b/thirdParty/qserialport/confapp.pri new file mode 100644 index 0000000000000000000000000000000000000000..3cd0e76dbe8f1fb2bad656bb9fed9857a97e24f4 --- /dev/null +++ b/thirdParty/qserialport/confapp.pri @@ -0,0 +1,24 @@ +## +## Unofficial Qt Serial Port Library +## +## Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. +## +## This program is free software: you can redistribute it and/or modify it +## under the terms of the GNU Lesser General Public License as published by the +## Free Software Foundation, either version 3 of the License, or (at your +## option) any later version. +## +## This program is distributed in the hope that it will be useful, but WITHOUT +## ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or +## FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for +## more details. +## +## You should have received a copy of the GNU Lesser General Public License +## along with this program. If not, see +## +## +## @file qserialport.prf +## www.inbiza.com +## + +CONFIG += release diff --git a/thirdParty/qserialport/configure b/thirdParty/qserialport/configure new file mode 100755 index 0000000000000000000000000000000000000000..3783501c345fa34de61eb6c42656b32a5bdacda0 --- /dev/null +++ b/thirdParty/qserialport/configure @@ -0,0 +1,1266 @@ +#!/bin/sh +# +# Generated by qconf 1.4 ( http://delta.affinix.com/qconf/ ) +# + +show_usage() { +cat </dev/null` + if echo $WHICH | grep 'shell built-in command' >/dev/null 2>&1; then + WHICH=which + elif [ -z "$WHICH" ]; then + if which which >/dev/null 2>&1; then + WHICH=which + else + for a in /usr/ucb /usr/bin /bin /usr/local/bin; do + if [ -x $a/which ]; then + WHICH=$a/which + break; + fi + done + fi + fi + + if [ -z "$WHICH" ]; then + OLD_IFS=$IFS + IFS=: + for a in $PATH; do + if [ -x $a/$1 ]; then + echo "$a/$1" + IFS=$OLD_IFS + export IFS + HOME=$OLD_HOME + export HOME + return 0 + fi + done + IFS=$OLD_IFS + export IFS + else + a=`"$WHICH" "$1" 2>/dev/null` + if [ ! -z "$a" -a -x "$a" ]; then + echo "$a" + HOME=$OLD_HOME + export HOME + return 0 + fi + fi + HOME=$OLD_HOME + export HOME + return 1 +} +WHICH=which_command + +# find a make command +if [ -z "$MAKE" ]; then + MAKE= + for mk in gmake make; do + if $WHICH $mk >/dev/null 2>&1; then + MAKE=`$WHICH $mk` + break + fi + done + if [ -z "$MAKE" ]; then + echo "You don't seem to have 'make' or 'gmake' in your PATH." + echo "Cannot proceed." + exit 1 + fi +fi + +show_qt_info() { + printf "Be sure you have a proper Qt 4.0 build environment set up. This means not\n" + printf "just Qt, but also a C++ compiler, a make tool, and any other packages\n" + printf "necessary for compiling C++ programs.\n" + printf "\n" + printf "If you are certain everything is installed, then it could be that Qt 4 is not\n" + printf "being recognized or that a different version of Qt is being detected by\n" + printf "mistake (for example, this could happen if \$QTDIR is pointing to a Qt 3\n" + printf "installation). At least one of the following conditions must be satisfied:\n" + printf "\n" + printf " 1) --qtdir is set to the location of Qt\n" + printf " 2) \$QTDIR is set to the location of Qt\n" + printf " 3) QtCore is in the pkg-config database\n" + printf " 4) qmake is in the \$PATH\n" + printf "\n" + printf "This script will use the first one it finds to be true, checked in the above\n" + printf "order. #3 and #4 are the recommended options. #1 and #2 are mainly for\n" + printf "overriding the system configuration.\n" + printf "\n" +} + +while [ $# -gt 0 ]; do + optarg=`expr "x$1" : 'x[^=]*=\(.*\)'` + case "$1" in + --prefix=*) + PREFIX=$optarg + shift + ;; + + --bindir=*) + BINDIR=$optarg + shift + ;; + + --datadir=*) + DATADIR=$optarg + shift + ;; + + --qtdir=*) + EX_QTDIR=$optarg + shift + ;; + + --verbose) + QC_VERBOSE="Y" + shift + ;; + --help) show_usage; exit ;; + *) show_usage; exit ;; + esac +done + +PREFIX=${PREFIX:-/usr/local} +BINDIR=${BINDIR:-$PREFIX/bin} +DATADIR=${DATADIR:-$PREFIX/share} + +echo "Configuring QSerialPort ..." + +if [ "$QC_VERBOSE" = "Y" ]; then +echo +echo PREFIX=$PREFIX +echo BINDIR=$BINDIR +echo DATADIR=$DATADIR +echo EX_QTDIR=$EX_QTDIR +echo +fi + +printf "Verifying Qt 4 build environment ... " + +# run qmake -v and check version +qmake_check_v4() { + if [ -x "$1" ]; then + if echo `$1 -v 2>&1` | grep "Qt version 4\." >/dev/null 2>&1; then + return 0 + elif [ "$QC_VERBOSE" = "Y" ]; then + echo "Warning: $1 not for Qt 4" + fi + fi + return 1 +} + +if [ "$QC_VERBOSE" = "Y" ]; then + echo +fi + +qm="" +names="qmake-qt4 qmake4 qmake" + +# qt4 check: --qtdir +if [ -z "$qm" ] && [ ! -z "$EX_QTDIR" ]; then + for n in $names; do + qstr=$EX_QTDIR/bin/$n + if qmake_check_v4 "$qstr"; then + qm=$qstr + break; + fi + done +fi +if [ -z "$qm" ] && [ "$QC_VERBOSE" = "Y" ]; then + echo "Warning: qmake not found via --qtdir" +fi + +# qt4 check: QTDIR +if [ -z "$qm" ] && [ ! -z "$QTDIR" ]; then + for n in $names; do + qstr=$QTDIR/bin/$n + if qmake_check_v4 "$qstr"; then + qm=$qstr + break; + fi + done +fi +if [ -z "$qm" ] && [ "$QC_VERBOSE" = "Y" ]; then + echo "Warning: qmake not found via \$QTDIR" +fi + +# qt4 check: pkg-config +if [ -z "$qm" ]; then + str=`pkg-config QtCore --variable=exec_prefix 2>/dev/null` + if [ ! -z "$str" ]; then + for n in $names; do + qstr=$str/bin/$n + if qmake_check_v4 "$qstr"; then + qm=$qstr + break; + fi + done + fi +fi +if [ -z "$qm" ] && [ "$QC_VERBOSE" = "Y" ]; then + echo "Warning: qmake not found via pkg-config" +fi + +# qt4 check: PATH +if [ -z "$qm" ]; then + for n in $names; do + qstr=`$WHICH $n 2>/dev/null` + if qmake_check_v4 "$qstr"; then + qm=$qstr + break; + fi + done +fi +if [ -z "$qm" ] && [ "$QC_VERBOSE" = "Y" ]; then + echo "Warning: qmake not found via \$PATH" +fi + +if [ -z "$qm" ]; then + if [ "$QC_VERBOSE" = "Y" ]; then + echo " -> fail" + else + echo "fail" + fi + printf "\n" + printf "Reason: Unable to find the 'qmake' tool for Qt 4.\n" + printf "\n" + show_qt_info + exit 1; +fi +if [ "$QC_VERBOSE" = "Y" ]; then + echo qmake found in $qm +fi + +gen_files() { +cat >$1/modules.cpp <$1/modules_new.cpp <$1/conf4.h < + +class Conf; + +enum VersionMode { VersionMin, VersionExact, VersionMax, VersionAny }; + +// ConfObj +// +// Subclass ConfObj to create a new configuration module. +class ConfObj +{ +public: + Conf *conf; + bool required; + bool disabled; + bool success; + + ConfObj(Conf *c); + virtual ~ConfObj(); + + // long or descriptive name of what is being checked/performed + // example: "KDE >= 3.3" + virtual QString name() const = 0; + + // short name + // example: "kde" + virtual QString shortname() const = 0; + + // string to display during check + // default: "Checking for [name] ..." + virtual QString checkString() const; + + // string to display after check + // default: "yes" or "no", based on result of exec() + virtual QString resultString() const; + + // this is where the checking code goes + virtual bool exec() = 0; +}; + +// Conf +// +// Interact with this class from your ConfObj to perform detection +// operations and to output configuration parameters. +class Conf +{ +public: + bool debug_enabled; + QString qmake_path; + QString maketool; + + QString DEFINES; + QString INCLUDEPATH; + QString LIBS; + QString extra; + + QList list; + QMap vars; + + Conf(); + ~Conf(); + + QString getenv(const QString &var); + QString qvar(const QString &s); + + bool exec(); + + void debug(const QString &s); + + QString expandIncludes(const QString &inc); + QString expandLibs(const QString &lib); + + int doCommand(const QString &s, QByteArray *out = 0); + int doCommand(const QString &prog, const QStringList &args, QByteArray *out = 0); + + bool doCompileAndLink(const QString &filedata, const QStringList &incs, const QString &libs, const QString &proextra, int *retcode = 0); + bool checkHeader(const QString &path, const QString &h); + bool findHeader(const QString &h, const QStringList &ext, QString *inc); + bool checkLibrary(const QString &path, const QString &name); + bool findLibrary(const QString &name, QString *lib); + QString findProgram(const QString &prog); + bool findSimpleLibrary(const QString &incvar, const QString &libvar, const QString &incname, const QString &libname, QString *incpath, QString *libs); + bool findFooConfig(const QString &path, QString *version, QStringList *incs, QString *libs, QString *otherflags); + bool findPkgConfig(const QString &name, VersionMode mode, const QString &req_version, QString *version, QStringList *incs, QString *libs, QString *otherflags); + + void addDefine(const QString &str); + void addLib(const QString &str); + void addIncludePath(const QString &str); + void addExtra(const QString &str); + +private: + bool first_debug; + + friend class ConfObj; + void added(ConfObj *o); +}; + +#endif + +EOT +cat >$1/conf4.cpp < +#include + +class MocTestObject : public QObject +{ + Q_OBJECT +public: + MocTestObject() {} +}; + +QString qc_getenv(const QString &var) +{ + char *p = ::getenv(var.toLatin1().data()); + if(!p) + return QString(); + return QString(p); +} + +QStringList qc_pathlist() +{ + QStringList list; + QString path = qc_getenv("PATH"); + if(!path.isEmpty()) + list = path.split(':', QString::SkipEmptyParts); + return list; +} + +QString qc_findprogram(const QString &prog) +{ + QString out; + QStringList list = qc_pathlist(); + for(int n = 0; n < list.count(); ++n) + { + QFileInfo fi(list[n] + '/' + prog); + if(fi.exists() && fi.isExecutable()) + { + out = fi.filePath(); + break; + } + } + return out; +} + +QString qc_findself(const QString &argv0) +{ + if(argv0.contains('/')) + return argv0; + else + return qc_findprogram(argv0); +} + +int qc_runcommand(const QString &command, QByteArray *out, bool showOutput) +{ + QString fullcmd = command; + if(!showOutput) + fullcmd += " 2>/dev/null"; + FILE *f = popen(fullcmd.toLatin1().data(), "r"); + if(!f) + return -1; + if(out) + out->clear(); + while(1) + { + char c = (char)fgetc(f); + if(feof(f)) + break; + if(out) + out->append(c); + if(showOutput) + fputc(c, stdout); + } + int ret = pclose(f); + if(ret == -1) + return -1; + return ret; +} + +int qc_runprogram(const QString &prog, const QStringList &args, QByteArray *out, bool showOutput) +{ + QString fullcmd = prog; + QString argstr = args.join(" "); + if(!argstr.isEmpty()) + fullcmd += QString(" ") + argstr; + return qc_runcommand(fullcmd, out, showOutput); + + // TODO: use QProcess once it is fixed + /* + QProcess process; + if(showOutput) + process.setReadChannelMode(ForwardedChannels); + process.start(prog, args); + process.waitForFinished(-1); + return process.exitCode(); + */ +} + +bool qc_removedir(const QString &dirPath) +{ + QDir dir(dirPath); + if(!dir.exists()) + return false; + QStringList list = dir.entryList(); + foreach(QString s, list) + { + if(s == "." || s == "..") + continue; + QFileInfo fi(dir.filePath(s)); + if(fi.isDir()) + { + if(!qc_removedir(fi.filePath())) + return false; + } + else + { + if(!dir.remove(s)) + return false; + } + } + QString dirName = dir.dirName(); + if(!dir.cdUp()) + return false; + if(!dir.rmdir(dirName)) + return false; + return true; +} + +void qc_splitcflags(const QString &cflags, QStringList *incs, QStringList *otherflags) +{ + incs->clear(); + otherflags->clear(); + + QStringList cflagsList = cflags.split(" "); + for(int n = 0; n < cflagsList.count(); ++n) + { + QString str = cflagsList[n]; + if(str.startsWith("-I")) + { + // we want everything except the leading "-I" + incs->append(str.remove(0, 2)); + } + else + { + // we want whatever is left + otherflags->append(str); + } + } +} + +QString qc_escapeArg(const QString &str) +{ + QString out; + for(int n = 0; n < (int)str.length(); ++n) { + if(str[n] == '-') + out += '_'; + else + out += str[n]; + } + return out; +} + +//---------------------------------------------------------------------------- +// ConfObj +//---------------------------------------------------------------------------- +ConfObj::ConfObj(Conf *c) +{ + conf = c; + conf->added(this); + required = false; + disabled = false; + success = false; +} + +ConfObj::~ConfObj() +{ +} + +QString ConfObj::checkString() const +{ + return QString("Checking for %1 ...").arg(name()); +} + +QString ConfObj::resultString() const +{ + if(success) + return "yes"; + else + return "no"; +} + +//---------------------------------------------------------------------------- +// qc_internal_pkgconfig +//---------------------------------------------------------------------------- +class qc_internal_pkgconfig : public ConfObj +{ +public: + QString pkgname, desc; + VersionMode mode; + QString req_ver; + + qc_internal_pkgconfig(Conf *c, const QString &_name, const QString &_desc, VersionMode _mode, const QString &_req_ver) : ConfObj(c) + { + pkgname = _name; + desc = _desc; + mode = _mode; + req_ver = _req_ver; + } + + QString name() const { return desc; } + QString shortname() const { return pkgname; } + + bool exec() + { + QStringList incs; + QString version, libs, other; + if(!conf->findPkgConfig(pkgname, mode, req_ver, &version, &incs, &libs, &other)) + return false; + + for(int n = 0; n < incs.count(); ++n) + conf->addIncludePath(incs[n]); + if(!libs.isEmpty()) + conf->addLib(libs); + //if(!other.isEmpty()) + // conf->addExtra(QString("QMAKE_CFLAGS += %1\n").arg(other)); + return true; + } +}; + +//---------------------------------------------------------------------------- +// Conf +//---------------------------------------------------------------------------- +Conf::Conf() +{ + // TODO: no more vars? + //vars.insert("QMAKE_INCDIR_X11", new QString(X11_INC)); + //vars.insert("QMAKE_LIBDIR_X11", new QString(X11_LIBDIR)); + //vars.insert("QMAKE_LIBS_X11", new QString(X11_LIB)); + //vars.insert("QMAKE_CC", CC); + + debug_enabled = false; +} + +Conf::~Conf() +{ + qDeleteAll(list); +} + +void Conf::added(ConfObj *o) +{ + list.append(o); +} + +QString Conf::getenv(const QString &var) +{ + return qc_getenv(var); +} + +void Conf::debug(const QString &s) +{ + if(debug_enabled) + { + if(first_debug) + printf("\n"); + first_debug = false; + printf(" * %s\n", qPrintable(s)); + } +} + +bool Conf::exec() +{ + for(int n = 0; n < list.count(); ++n) + { + ConfObj *o = list[n]; + + // if this was a disabled-by-default option, check if it was enabled + if(o->disabled) + { + QString v = QString("QC_ENABLE_") + qc_escapeArg(o->shortname()); + if(getenv(v) != "Y") + continue; + } + // and the opposite? + else + { + QString v = QString("QC_DISABLE_") + qc_escapeArg(o->shortname()); + if(getenv(v) == "Y") + continue; + } + + bool output = true; + QString check = o->checkString(); + if(check.isEmpty()) + output = false; + + if(output) + { + printf("%s", check.toLatin1().data()); + fflush(stdout); + } + + first_debug = true; + bool ok = o->exec(); + o->success = ok; + + if(output) + { + QString result = o->resultString(); + if(!first_debug) + printf(" -> %s\n", result.toLatin1().data()); + else + printf(" %s\n", result.toLatin1().data()); + } + + if(!ok && o->required) + { + printf("\nError: need %s!\n", o->name().toLatin1().data()); + return false; + } + } + return true; +} + +QString Conf::qvar(const QString &s) +{ + return vars.value(s); +} + +QString Conf::expandIncludes(const QString &inc) +{ + return QString("-I") + inc; +} + +QString Conf::expandLibs(const QString &lib) +{ + return QString("-L") + lib; +} + +int Conf::doCommand(const QString &s, QByteArray *out) +{ + debug(QString("[%1]").arg(s)); + int r = qc_runcommand(s, out, debug_enabled); + debug(QString("returned: %1").arg(r)); + return r; +} + +int Conf::doCommand(const QString &prog, const QStringList &args, QByteArray *out) +{ + QString fullcmd = prog; + QString argstr = args.join(" "); + if(!argstr.isEmpty()) + fullcmd += QString(" ") + argstr; + debug(QString("[%1]").arg(fullcmd)); + int r = qc_runprogram(prog, args, out, debug_enabled); + debug(QString("returned: %1").arg(r)); + return r; +} + +bool Conf::doCompileAndLink(const QString &filedata, const QStringList &incs, const QString &libs, const QString &proextra, int *retcode) +{ + QDir tmp(".qconftemp"); + if(!tmp.mkdir("atest")) + { + debug("unable to create atest dir"); + return false; + } + QDir dir(tmp.filePath("atest")); + if(!dir.exists()) + { + debug("atest dir does not exist"); + return false; + } + + QString fname = dir.filePath("atest.cpp"); + QString out = "atest"; + QFile f(fname); + if(!f.open(QFile::WriteOnly | QFile::Truncate)) + { + debug("unable to open atest.cpp for writing"); + return false; + } + if(f.write(filedata.toLatin1()) == -1) + { + debug("error writing to atest.cpp"); + return false; + } + f.close(); + + debug(QString("Wrote atest.cpp:\n%1").arg(filedata)); + + QString pro = QString( + "CONFIG += console\n" + "CONFIG -= qt app_bundle\n" + "SOURCES += atest.cpp\n"); + QString inc = incs.join(" "); + if(!inc.isEmpty()) + pro += "INCLUDEPATH += " + inc + '\n'; + if(!libs.isEmpty()) + pro += "LIBS += " + libs + '\n'; + pro += proextra; + + fname = dir.filePath("atest.pro"); + f.setFileName(fname); + if(!f.open(QFile::WriteOnly | QFile::Truncate)) + { + debug("unable to open atest.pro for writing"); + return false; + } + if(f.write(pro.toLatin1()) == -1) + { + debug("error writing to atest.pro"); + return false; + } + f.close(); + + debug(QString("Wrote atest.pro:\n%1").arg(pro)); + + QString oldpath = QDir::currentPath(); + QDir::setCurrent(dir.path()); + + bool ok = false; + int r = doCommand(qmake_path, QStringList() << "atest.pro"); + if(r == 0) + { + r = doCommand(maketool, QStringList()); + if(r == 0) + { + ok = true; + if(retcode) + *retcode = doCommand(QString("./") + out, QStringList()); + } + r = doCommand(maketool, QStringList() << "distclean"); + if(r != 0) + debug("error during atest distclean"); + } + + QDir::setCurrent(oldpath); + + // cleanup + //dir.remove("atest.pro"); + //dir.remove("atest.cpp"); + //tmp.rmdir("atest"); + + // remove whole dir since distclean doesn't always work + qc_removedir(tmp.filePath("atest")); + + if(!ok) + return false; + return true; +} + +bool Conf::checkHeader(const QString &path, const QString &h) +{ + QFileInfo fi(path + '/' + h); + if(fi.exists()) + return true; + return false; +} + +bool Conf::findHeader(const QString &h, const QStringList &ext, QString *inc) +{ + if(checkHeader("/usr/include", h)) + { + *inc = ""; + return true; + } + QStringList dirs; + dirs += "/usr/local/include"; + dirs += ext; + for(QStringList::ConstIterator it = dirs.begin(); it != dirs.end(); ++it) + { + if(checkHeader(*it, h)) + { + *inc = *it; + return true; + } + } + return false; +} + +bool Conf::checkLibrary(const QString &path, const QString &name) +{ + QString str = + //"#include \n" + "int main()\n" + "{\n" + //" printf(\"library checker running\\\\n\");\n" + " return 0;\n" + "}\n"; + + QString libs; + if(!path.isEmpty()) + libs += QString("-L") + path + ' '; + libs += QString("-l") + name; + if(!doCompileAndLink(str, QStringList(), libs, QString())) + return false; + return true; +} + +bool Conf::findLibrary(const QString &name, QString *lib) +{ + if(checkLibrary("", name)) + { + *lib = ""; + return true; + } + if(checkLibrary("/usr/local/lib", name)) + { + *lib = "/usr/local/lib"; + return true; + } + return false; +} + +QString Conf::findProgram(const QString &prog) +{ + return qc_findprogram(prog); +} + +bool Conf::findSimpleLibrary(const QString &incvar, const QString &libvar, const QString &incname, const QString &libname, QString *incpath, QString *libs) +{ + QString inc, lib; + QString s; + + s = getenv(incvar); + if(!s.isEmpty()) { + if(!checkHeader(s, incname)) + return false; + inc = s; + } + else { + if(!findHeader(incname, QStringList(), &s)) + return false; + inc = s; + } + + s = getenv(libvar); + if(!s.isEmpty()) { + if(!checkLibrary(s, libname)) + return false; + lib = s; + } + else { + if(!findLibrary(libname, &s)) + return false; + lib = s; + } + + QString lib_out; + if(!lib.isEmpty()) + lib_out += QString("-L") + s; + lib_out += QString("-l") + libname; + + *incpath = inc; + *libs = lib_out; + return true; +} + +bool Conf::findFooConfig(const QString &path, QString *version, QStringList *incs, QString *libs, QString *otherflags) +{ + QStringList args; + QByteArray out; + int ret; + + args += "--version"; + ret = doCommand(path, args, &out); + if(ret != 0) + return false; + + QString version_out = QString::fromLatin1(out).trimmed(); + + args.clear(); + args += "--libs"; + ret = doCommand(path, args, &out); + if(ret != 0) + return false; + + QString libs_out = QString::fromLatin1(out).trimmed(); + + args.clear(); + args += "--cflags"; + ret = doCommand(path, args, &out); + if(ret != 0) + return false; + + QString cflags = QString::fromLatin1(out).trimmed(); + + QStringList incs_out, otherflags_out; + qc_splitcflags(cflags, &incs_out, &otherflags_out); + + *version = version_out; + *incs = incs_out; + *libs = libs_out; + *otherflags = otherflags_out.join(" "); + return true; +} + +bool Conf::findPkgConfig(const QString &name, VersionMode mode, const QString &req_version, QString *version, QStringList *incs, QString *libs, QString *otherflags) +{ + QStringList args; + QByteArray out; + int ret; + + args += name; + args += "--exists"; + ret = doCommand("pkg-config", args, &out); + if(ret != 0) + return false; + + if(mode != VersionAny) + { + args.clear(); + args += name; + if(mode == VersionMin) + args += QString("--atleast-version=%1").arg(req_version); + else if(mode == VersionMax) + args += QString("--max-version=%1").arg(req_version); + else + args += QString("--exact-version=%1").arg(req_version); + ret = doCommand("pkg-config", args, &out); + if(ret != 0) + return false; + } + + args.clear(); + args += name; + args += "--modversion"; + ret = doCommand("pkg-config", args, &out); + if(ret != 0) + return false; + + QString version_out = QString::fromLatin1(out).trimmed(); + + args.clear(); + args += name; + args += "--libs"; + ret = doCommand("pkg-config", args, &out); + if(ret != 0) + return false; + + QString libs_out = QString::fromLatin1(out).trimmed(); + + args.clear(); + args += name; + args += "--cflags"; + ret = doCommand("pkg-config", args, &out); + if(ret != 0) + return false; + + QString cflags = QString::fromLatin1(out).trimmed(); + + QStringList incs_out, otherflags_out; + qc_splitcflags(cflags, &incs_out, &otherflags_out); + + *version = version_out; + *incs = incs_out; + *libs = libs_out; + *otherflags = otherflags_out.join(" "); + return true; +} + +void Conf::addDefine(const QString &str) +{ + if(DEFINES.isEmpty()) + DEFINES = str; + else + DEFINES += QString(" ") + str; + debug(QString("DEFINES += %1").arg(str)); +} + +void Conf::addLib(const QString &str) +{ + if(LIBS.isEmpty()) + LIBS = str; + else + LIBS += QString(" ") + str; + debug(QString("LIBS += %1").arg(str)); +} + +void Conf::addIncludePath(const QString &str) +{ + if(INCLUDEPATH.isEmpty()) + INCLUDEPATH = str; + else + INCLUDEPATH += QString(" ") + str; + debug(QString("INCLUDEPATH += %1").arg(str)); +} + +void Conf::addExtra(const QString &str) +{ + extra += str + '\n'; + debug(QString("extra += %1").arg(str)); +} + +//---------------------------------------------------------------------------- +// main +//---------------------------------------------------------------------------- +#include "conf4.moc" + +#ifdef HAVE_MODULES +# include"modules.cpp" +#endif + +int main() +{ + Conf *conf = new Conf; + ConfObj *o; + o = 0; +#ifdef HAVE_MODULES +# include"modules_new.cpp" +#endif + + conf->debug_enabled = (qc_getenv("QC_VERBOSE") == "Y") ? true: false; + if(conf->debug_enabled) + printf(" -> ok\n"); + else + printf("ok\n"); + + QString confCommand = qc_getenv("QC_COMMAND"); + QString proName = qc_getenv("QC_PROFILE"); + conf->qmake_path = qc_getenv("QC_QMAKE"); + conf->maketool = qc_getenv("QC_MAKETOOL"); + + if(conf->debug_enabled) + printf("conf command: [%s]\n", qPrintable(confCommand)); + + QString confPath = qc_findself(confCommand); + if(confPath.isEmpty()) + { + printf("Error: cannot find myself; rerun with an absolute path\n"); + return 1; + } + + QString srcdir = QFileInfo(confPath).absolutePath(); + QString builddir = QDir::current().absolutePath(); + QString proPath = QDir(srcdir).filePath(proName); + + if(conf->debug_enabled) + { + printf("conf path: [%s]\n", qPrintable(confPath)); + printf("srcdir: [%s]\n", qPrintable(srcdir)); + printf("builddir: [%s]\n", qPrintable(builddir)); + printf("profile: [%s]\n", qPrintable(proPath)); + printf("qmake path: [%s]\n", qPrintable(conf->qmake_path)); + printf("make tool: [%s]\n", qPrintable(conf->maketool)); + printf("\n"); + } + + bool success = false; + if(conf->exec()) + { + QFile f("conf.pri"); + if(!f.open(QFile::WriteOnly | QFile::Truncate)) + { + printf("Error writing %s\n", qPrintable(f.fileName())); + return 1; + } + + QString str; + str += "# qconf\n\n"; + + QString var; + var = qc_getenv("PREFIX"); + if(!var.isEmpty()) + str += QString("PREFIX = %1\n").arg(var); + var = qc_getenv("BINDIR"); + if(!var.isEmpty()) + str += QString("BINDIR = %1\n").arg(var); + var = qc_getenv("INCDIR"); + if(!var.isEmpty()) + str += QString("INCDIR = %1\n").arg(var); + var = qc_getenv("LIBDIR"); + if(!var.isEmpty()) + str += QString("LIBDIR = %1\n").arg(var); + var = qc_getenv("DATADIR"); + if(!var.isEmpty()) + str += QString("DATADIR = %1\n").arg(var); + str += '\n'; + + if(qc_getenv("QC_STATIC") == "Y") + str += "CONFIG += staticlib\n"; + + // TODO: don't need this? + //str += "QT_PATH_PLUGINS = " + QString(qInstallPathPlugins()) + '\n'; + + if(!conf->DEFINES.isEmpty()) + str += "DEFINES += " + conf->DEFINES + '\n'; + if(!conf->INCLUDEPATH.isEmpty()) + str += "INCLUDEPATH += " + conf->INCLUDEPATH + '\n'; + if(!conf->LIBS.isEmpty()) + str += "LIBS += " + conf->LIBS + '\n'; + if(!conf->extra.isEmpty()) + str += conf->extra; + str += '\n'; + + QByteArray cs = str.toLatin1(); + f.write(cs); + f.close(); + success = true; + } + QString qmake_path = conf->qmake_path; + delete conf; + + if(!success) + return 1; + + // run qmake on the project file + int ret = qc_runprogram(qmake_path, QStringList() << proPath, 0, true); + if(ret != 0) + return 1; + + return 0; +} + +EOT +cat >$1/conf4.pro </dev/null + $MAKE clean >/dev/null 2>&1 + $MAKE >../conf.log 2>&1 +) + +if [ "$?" != "0" ]; then + rm -rf .qconftemp + if [ "$QC_VERBOSE" = "Y" ]; then + echo " -> fail" + else + echo "fail" + fi + printf "\n" + printf "Reason: There was an error compiling 'conf'. See conf.log for details.\n" + printf "\n" + show_qt_info + if [ "$QC_VERBOSE" = "Y" ]; then + echo "conf.log:" + cat conf.log + fi + exit 1; +fi + +QC_COMMAND=$0 +export QC_COMMAND +QC_PROFILE=qserialport.pro +export QC_PROFILE +QC_QMAKE=$qm +export QC_QMAKE +QC_MAKETOOL=$MAKE +export QC_MAKETOOL +.qconftemp/conf +ret="$?" +if [ "$ret" = "1" ]; then + rm -rf .qconftemp + echo + exit 1; +else + if [ "$ret" != "0" ]; then + rm -rf .qconftemp + if [ "$QC_VERBOSE" = "Y" ]; then + echo " -> fail" + else + echo "fail" + fi + echo + echo "Reason: Unexpected error launching 'conf'" + echo + exit 1; + fi +fi +rm -rf .qconftemp + +echo +echo "Good, your configure finished. Now run $MAKE." +echo diff --git a/thirdParty/qserialport/configure.exe b/thirdParty/qserialport/configure.exe new file mode 100644 index 0000000000000000000000000000000000000000..4050bafe0117902034091b955dc364372de98610 Binary files /dev/null and b/thirdParty/qserialport/configure.exe differ diff --git a/thirdParty/qserialport/examples/echo_eventmode/echo_eventmode.pro b/thirdParty/qserialport/examples/echo_eventmode/echo_eventmode.pro new file mode 100644 index 0000000000000000000000000000000000000000..d719468fda1c50526292ebf1445129573927373d --- /dev/null +++ b/thirdParty/qserialport/examples/echo_eventmode/echo_eventmode.pro @@ -0,0 +1,48 @@ +## +## Unofficial Qt Serial Port Library +## +## Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. +## +## This program is free software: you can redistribute it and/or modify it +## under the terms of the GNU Lesser General Public License as published by the +## Free Software Foundation, either version 3 of the License, or (at your +## option) any later version. +## +## This program is distributed in the hope that it will be useful, but WITHOUT +## ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or +## FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for +## more details. +## +## You should have received a copy of the GNU Lesser General Public License +## along with this program. If not, see +## +## +## @file echo_eventmode.pro +## www.inbiza.com +## + + +include(../examples.pri) + +DEPENDPATH += . $$QSERIALPORT_INCBASE/QtSerialPort + +QT += network +!windows:TARGET = $$QSERIALPORT_BINDESTDIR/$$TARGET + +# Input +SOURCES += main.cpp \ + host.cpp + +HEADERS += host.h + +MOC_DIR = $$QSERIALPORT_BUILDDIR/GeneratedFiles/eventdriven + +CONFIG(debug, debug|release) { + OBJECTS_DIR = $$QSERIALPORT_BUILDDIR/Debug/eventdriven + macx:TARGET = $$member(TARGET, 0)_debug + windows:TARGET = $$member(TARGET, 0)d + unix:!macx:TARGET = $$member(TARGET, 0).debug +} +else { + OBJECTS_DIR = $$QSERIALPORT_BUILDDIR/Release/eventdriven +} diff --git a/thirdParty/qserialport/examples/echo_eventmode/host.cpp b/thirdParty/qserialport/examples/echo_eventmode/host.cpp new file mode 100644 index 0000000000000000000000000000000000000000..be17a1b00e53be68024ec36938bfe46f5baef234 --- /dev/null +++ b/thirdParty/qserialport/examples/echo_eventmode/host.cpp @@ -0,0 +1,75 @@ +/* + * Unofficial Qt Serial Port Library + * + * Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. + * + * This program is free software: you can redistribute it and/or modify it + * under the terms of the GNU Lesser General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This program is distributed in the hope that it will be useful, but WITHOUT + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + * more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see + * + * author labs@inbiza.com + */ + +#include +#include +#include +#include +#include +#include +#include "host.h" + +Host::Host(TNX::QSerialPort &serPort, QObject *parent) + : QObject(parent), serialPort_(serPort), timerId_(0), byteCounter_(0) +{ + using TNX::QSerialPort; + + timerId_ = startTimer(5000); + connect(&serialPort_, SIGNAL(readyRead()), SLOT(onDataReceived())); + + if ( !serialPort_.setCommTimeouts(QSerialPort::CtScheme_NonBlockingRead) ) + qWarning("Cannot set communications timeout values at port %s.", qPrintable(serialPort_.portName())); +} + +Host::~Host() +{ +} + +void Host::onDataReceived() +{ + if ( timerId_ ) + killTimer(timerId_); + + QByteArray data = serialPort_.read(512); + byteCounter_ += data.size(); + + std::cout << "Thread id: " << QThread::currentThreadId() << " Received data @ " << + qPrintable(QDateTime::currentDateTime().toString("hh:mm:ss.zzz")) << ". Echo back." << std::endl; + serialPort_.write(data); + + if ( byteCounter_ >= 4096 ) { + std::cout << "Event-Driven example is terminated successfully." << std::endl; + qApp->exit(0); + } + + // create a wait timer for the next packet + timerId_ = startTimer(5000); // 5sec +} + +void Host::timerEvent(QTimerEvent *event) +{ + Q_ASSERT(timerId_ == event->timerId()); + + killTimer(event->timerId()); + timerId_ = 0; + + std::cout << "Timeout occurred." << std::endl; +} diff --git a/thirdParty/qserialport/examples/echo_eventmode/host.h b/thirdParty/qserialport/examples/echo_eventmode/host.h new file mode 100644 index 0000000000000000000000000000000000000000..35d1ed634da0469b2ec0dad0060cfb0f6b98994c --- /dev/null +++ b/thirdParty/qserialport/examples/echo_eventmode/host.h @@ -0,0 +1,51 @@ +/* + * Unofficial Qt Serial Port Library + * + * Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. + * + * This program is free software: you can redistribute it and/or modify it + * under the terms of the GNU Lesser General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This program is distributed in the hope that it will be useful, but WITHOUT + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + * more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see + * + * author labs@inbiza.com + */ + +#ifndef HOST_H__ +#define HOST_H__ + +#include + +class QTimerEvent; + +namespace TNX { class QSerialPort; } + +class Host : public QObject +{ +Q_OBJECT + +public: + Host(TNX::QSerialPort &serPort, QObject *parent = 0); + ~Host(); + +protected: + virtual void timerEvent(QTimerEvent *event); + +private slots: + void onDataReceived(); + +private: + TNX::QSerialPort &serialPort_; + int timerId_; + int byteCounter_; +}; + +#endif // HOST_H__ diff --git a/thirdParty/qserialport/examples/echo_eventmode/main.cpp b/thirdParty/qserialport/examples/echo_eventmode/main.cpp new file mode 100644 index 0000000000000000000000000000000000000000..663ebfdc3f4a6941888f34c9d5f1e063cb93da4c --- /dev/null +++ b/thirdParty/qserialport/examples/echo_eventmode/main.cpp @@ -0,0 +1,94 @@ +/* + * Unofficial Qt Serial Port Library + * + * Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. + * + * This program is free software: you can redistribute it and/or modify it + * under the terms of the GNU Lesser General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This program is distributed in the hope that it will be useful, but WITHOUT + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + * more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see + * + * author labs@inbiza.com + */ + +#include +#include +#include +#include +#include +#include +#include +#include "host.h" + +void printHelp() +{ + std::cout << "Usage: echo_eventmode [--help] [--port=] [--set=]" << std::endl; + std::cout << std::endl; +#if defined(Q_OS_WIN) + std::cout << "Example: echo_eventmode --port=COM3 --set=9600,8,N,1" << std::endl; +#else + std::cout << "Example: echo_eventmode --port=/dev/ttyS0 --set=9600,8,N,1" << std::endl; +#endif +} + +bool processArgs(const QStringList &args, QString &serPort, QString &settings) +{ + QHash argPairs; + + foreach( QString ar, args ) { + if ( ar.split('=').size() == 2 ) { + argPairs.insert(ar.split('=').at(0), ar.split('=').at(1)); + } + else { + if ( ar == "--help" ) + goto LPrintHelpAndExit; + } + } + + settings = argPairs.value("--set", "9600,8,n,1"); +#if defined(Q_OS_WIN) + serPort = argPairs.value("--port", "COM3"); +#else + serPort = argPairs.value("--port", "/dev/ttyS0"); +#endif + + return true; + +LPrintHelpAndExit: + printHelp(); + return false; +} + +int main(int argc, char *argv[]) +{ + using TNX::QSerialPort; + + QCoreApplication a(argc, argv); + + std::cout << "Serial port echo example with event-driven model, Copyright (c) 2010 Inbiza Systems Inc." << std::endl; + std::cout << "Created by Inbiza Labs " << std::endl; + std::cout << std::endl; + std::cout << "Main thread id: " << QThread::currentThreadId() << std::endl; + + QString portName; + QString settings; + + if ( !processArgs(a.arguments(), portName, settings) ) + return 0; + + QSerialPort serport(portName, settings); + if ( !serport.open() ) + qFatal("Cannot open serial port %s. Exiting..", qPrintable(portName)); + + Host host(serport); + + return a.exec(); +} diff --git a/thirdParty/qserialport/examples/echo_pollingmode/echo_pollingmode.pro b/thirdParty/qserialport/examples/echo_pollingmode/echo_pollingmode.pro new file mode 100644 index 0000000000000000000000000000000000000000..6dfbfbc53620e0d21935ec6395b375e76ef7178d --- /dev/null +++ b/thirdParty/qserialport/examples/echo_pollingmode/echo_pollingmode.pro @@ -0,0 +1,46 @@ +## +## Unofficial Qt Serial Port Library +## +## Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. +## +## This program is free software: you can redistribute it and/or modify it +## under the terms of the GNU Lesser General Public License as published by the +## Free Software Foundation, either version 3 of the License, or (at your +## option) any later version. +## +## This program is distributed in the hope that it will be useful, but WITHOUT +## ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or +## FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for +## more details. +## +## You should have received a copy of the GNU Lesser General Public License +## along with this program. If not, see +## +## +## @file echo_pollingmode.pro +## www.inbiza.com +## + +include(../examples.pri) + +DEPENDPATH += . $$QSERIALPORT_INCBASE/QtSerialPort + +QT += network +!windows:TARGET = $$QSERIALPORT_BINDESTDIR/$$TARGET + +# Input +SOURCES += main.cpp + +#HEADERS += + +MOC_DIR = $$QSERIALPORT_BUILDDIR/GeneratedFiles/polling + +CONFIG(debug, debug|release) { + OBJECTS_DIR = $$QSERIALPORT_BUILDDIR/Debug/polling + macx:TARGET = $$member(TARGET, 0)_debug + windows:TARGET = $$member(TARGET, 0)d + unix:!macx:TARGET = $$member(TARGET, 0).debug +} +else { + OBJECTS_DIR = $$QSERIALPORT_BUILDDIR/Release/polling +} diff --git a/thirdParty/qserialport/examples/echo_pollingmode/main.cpp b/thirdParty/qserialport/examples/echo_pollingmode/main.cpp new file mode 100644 index 0000000000000000000000000000000000000000..53d8da1bb8fb28fc325e1d75e8e52448203d4969 --- /dev/null +++ b/thirdParty/qserialport/examples/echo_pollingmode/main.cpp @@ -0,0 +1,111 @@ +/* + * Unofficial Qt Serial Port Library + * + * Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. + * + * This program is free software: you can redistribute it and/or modify it + * under the terms of the GNU Lesser General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This program is distributed in the hope that it will be useful, but WITHOUT + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + * more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see + * + * author labs@inbiza.com + */ + +#include +#include +#include +#include +#include +#include +#include + +void printHelp() +{ + std::cout << "Usage: echo_pollingmode [--help] [--port=] [--set=]" << std::endl; + std::cout << std::endl; +#if defined(Q_OS_WIN) + std::cout << "Example: echo_pollingmode --port=COM3 --set=9600,8,N,1" << std::endl; +#else + std::cout << "Example: echo_pollingmode --port=/dev/ttyS0 --set=9600,8,N,1" << std::endl; +#endif +} + +bool processArgs(const QStringList &args, QString &serPort, QString &settings) +{ + QHash argPairs; + + foreach( QString ar, args ) { + if ( ar.split('=').size() == 2 ) { + argPairs.insert(ar.split('=').at(0), ar.split('=').at(1)); + } + else { + if ( ar == "--help" ) + goto LPrintHelpAndExit; + } + } + + settings = argPairs.value("--set", "9600,8,n,1"); +#if defined(Q_OS_WIN) + serPort = argPairs.value("--port", "COM3"); +#else + serPort = argPairs.value("--port", "/dev/ttyS0"); +#endif + + return true; + +LPrintHelpAndExit: + printHelp(); + return false; +} + +int main(int argc, char *argv[]) +{ + using namespace TNX; + + QCoreApplication a(argc, argv); + + std::cout << "Serial port echo example with polling model, Copyright (c) 2010 Inbiza Systems Inc." << std::endl; + std::cout << "Created by Inbiza Labs " << std::endl; + + QString portName; + QString settings; + + if ( !processArgs(a.arguments(), portName, settings) ) + return 0; + + QSerialPort serport(portName, settings); + if ( !serport.open() ) + qFatal("Cannot open serial port %s. Exiting..", qPrintable(portName)); + + if ( !serport.setCommTimeouts(QSerialPort::CtScheme_NonBlockingRead) ) + qWarning("Cannot set communications timeout values at port %s.", qPrintable(portName)); + + int byteCounter = 0; + forever { + if ( serport.waitForReadyRead(5000) ) { // 5sec + QByteArray data = serport.read(512); + byteCounter += data.size(); + std::cout << "Received data @ " << qPrintable(QDateTime::currentDateTime().toString("hh:mm:ss.zzz")) << + ". Echo back." << std::endl; + serport.write(data); + if ( byteCounter >= 4096 ) + break; + } + else { + std::cout << "Timeout while waiting for incoming data @ " << + qPrintable(QDateTime::currentDateTime().toString("hh:mm:ss.zzz")) << std::endl; + } + } + + std::cout << "Polling example is terminated successfully." << std::endl; + return 0; +} + diff --git a/thirdParty/qserialport/examples/examples.pri b/thirdParty/qserialport/examples/examples.pri new file mode 100644 index 0000000000000000000000000000000000000000..46f7e3a0d397f63162902f03a44493bc0ea8f199 --- /dev/null +++ b/thirdParty/qserialport/examples/examples.pri @@ -0,0 +1,30 @@ +## +## Unofficial Qt Serial Port Library +## +## Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. +## +## This program is free software: you can redistribute it and/or modify it +## under the terms of the GNU Lesser General Public License as published by the +## Free Software Foundation, either version 3 of the License, or (at your +## option) any later version. +## +## This program is distributed in the hope that it will be useful, but WITHOUT +## ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or +## FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for +## more details. +## +## You should have received a copy of the GNU Lesser General Public License +## along with this program. If not, see +## +## +## @file examples.pri +## www.inbiza.com +## + +include(../app.pri) + +# default to console (individual programs can always override this if needed) + +CONFIG += console +CONFIG -= app_bundle +QT -= gui diff --git a/thirdParty/qserialport/examples/examples.pro b/thirdParty/qserialport/examples/examples.pro new file mode 100644 index 0000000000000000000000000000000000000000..e0f4ad65019cab9e3fac0acba5aae79032c16075 --- /dev/null +++ b/thirdParty/qserialport/examples/examples.pro @@ -0,0 +1,30 @@ +## +## Unofficial Qt Serial Port Library +## +## Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. +## +## This program is free software: you can redistribute it and/or modify it +## under the terms of the GNU Lesser General Public License as published by the +## Free Software Foundation, either version 3 of the License, or (at your +## option) any later version. +## +## This program is distributed in the hope that it will be useful, but WITHOUT +## ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or +## FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for +## more details. +## +## You should have received a copy of the GNU Lesser General Public License +## along with this program. If not, see +## +## +## @file examples.pro +## www.inbiza.com +## + +TEMPLATE = subdirs + +SUBDIRS += \ + tranceiver \ + serial2tcpbridge \ + echo_eventmode \ + echo_pollingmode diff --git a/thirdParty/qserialport/examples/serial2tcpbridge/host.cpp b/thirdParty/qserialport/examples/serial2tcpbridge/host.cpp new file mode 100644 index 0000000000000000000000000000000000000000..48f0f49d59dd1d64eaea4fcff8305fe486a9ce56 --- /dev/null +++ b/thirdParty/qserialport/examples/serial2tcpbridge/host.cpp @@ -0,0 +1,102 @@ +/* + * Unofficial Qt Serial Port Library + * + * Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. + * + * This program is free software: you can redistribute it and/or modify it + * under the terms of the GNU Lesser General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This program is distributed in the hope that it will be useful, but WITHOUT + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + * more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see + * + * author labs@inbiza.com + */ + +#include +#include +#include +#include +#include "host.h" + +Host::Host(const QString &serPort, int tcpPort, QObject *parent) + : QObject(parent), tcpPort_(tcpPort), tcpSocket_(NULL) +{ + using TNX::QSerialPort; + + serialPort_ = new QSerialPort(serPort, "9600,8,N,1", this); + tcpServer_ = new QTcpServer(this); +} + +Host::~Host() +{ + stop(); +} + +int Host::start() +{ + // deal with serial port + + if ( serialPort_->open() ) { + serialPort_->flushInBuffer(); + serialPort_->flushOutBuffer(); + } + else { + qFatal("Cannot open serial port: \"%s\". Giving up.", qPrintable(serialPort_->errorString())); + return -1; + } + connect(serialPort_, SIGNAL(readyRead()), SLOT(onDataReceivedSerial())); + + // deal with tcp port + + std::cout << "Waiting for connection on tcp port " << tcpPort_ << std::endl; + + if ( tcpServer_->listen(QHostAddress::Any, tcpPort_) ) { + std::cout << "Listening on " << qPrintable(tcpServer_->serverAddress().toString()) << ":" << tcpServer_->serverPort() << std::endl; + connect(tcpServer_, SIGNAL(newConnection()), SLOT(onNewTcpConnection())); + } + else { + qFatal("Cannot listening tcp port: \"%s\". Giving up.", qPrintable(tcpServer_->errorString())); + return -1; + } + + return 0; +} + +int Host::stop() +{ + serialPort_->close(); + disconnect(serialPort_, SIGNAL(readyRead()), this, SLOT(onDataReceivedSerial())); + + tcpServer_->close(); + disconnect(tcpServer_, SIGNAL(newConnection()), this, SLOT(onNewTcpConnection())); + + return 0; +} + +void Host::onDataReceivedNetwork() +{ + serialPort_->write(tcpSocket_->read(2048)); +} + +void Host::onDataReceivedSerial() +{ + if ( tcpSocket_->state() == QAbstractSocket::ConnectedState ) { + tcpSocket_->write(serialPort_->read(2048)); + } +} + +void Host::onNewTcpConnection() +{ + tcpSocket_ = tcpServer_->nextPendingConnection(); + + connect(tcpSocket_, SIGNAL(readyRead()), SLOT(onDataReceivedNetwork())); + + std::cout << "Connection is established with " << qPrintable(tcpSocket_->peerAddress().toString()) << std::endl; +} diff --git a/thirdParty/qserialport/examples/serial2tcpbridge/host.h b/thirdParty/qserialport/examples/serial2tcpbridge/host.h new file mode 100644 index 0000000000000000000000000000000000000000..8b4fe2b4303ec7f2dbb4c762cc57cd2e5076e12c --- /dev/null +++ b/thirdParty/qserialport/examples/serial2tcpbridge/host.h @@ -0,0 +1,53 @@ +/* + * Unofficial Qt Serial Port Library + * + * Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. + * + * This program is free software: you can redistribute it and/or modify it + * under the terms of the GNU Lesser General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This program is distributed in the hope that it will be useful, but WITHOUT + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + * more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see + * + * author labs@inbiza.com + */ + +#ifndef HOST_H__ +#define HOST_H__ + +#include + +class QTcpServer; +class QTcpSocket; +namespace TNX { class QSerialPort; } + +class Host : public QObject +{ +Q_OBJECT +public: + Host(const QString &serPort, int tcpPort, QObject *parent = 0); + ~Host(); + + int start(); + int stop(); + +private slots: + void onDataReceivedNetwork(); + void onDataReceivedSerial(); + void onNewTcpConnection(); + +private: + int tcpPort_; + TNX::QSerialPort *serialPort_; + QTcpServer *tcpServer_; + QTcpSocket *tcpSocket_; +}; + +#endif // HOST_H__ diff --git a/thirdParty/qserialport/examples/serial2tcpbridge/main.cpp b/thirdParty/qserialport/examples/serial2tcpbridge/main.cpp new file mode 100644 index 0000000000000000000000000000000000000000..7da03b953fc77343fd2347f53214de895f74dc49 --- /dev/null +++ b/thirdParty/qserialport/examples/serial2tcpbridge/main.cpp @@ -0,0 +1,117 @@ +/* + * Unofficial Qt Serial Port Library + * + * Copyright (c) 2010 Inbiza Systems Inc. All rights reserved. + * + * This program is free software: you can redistribute it and/or modify it + * under the terms of the GNU Lesser General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This program is distributed in the hope that it will be useful, but WITHOUT + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + * more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see + * + * author labs@inbiza.com + */ + +#include +#include +#include +#include +#include +#include +#include "host.h" +#include "proxy.h" + +void printHelp() +{ + std::cout << "Usage: ser2tcpbridge [--help] [--role= host|proxy] [--tcpport=] " \ + "[--serport=] [--remotehost=]" << std::endl; + std::cout << std::endl; + std::cout << "Example: ser2tcpbridge --role=host --serport=/dev/ttySAC0 --tcpport=8765" << std::endl; + std::cout << "Example: ser2tcpbridge --role=proxy --remotehost=192.168.0.23:8765" << std::endl; +} + +bool processArgs(const QStringList &args, QString &role, QString &serPort, QString &tcpPort, + QString &remoteHost) +{ + QHash argPairs; + + if ( args.size() < 2 ) + goto LPrintHelpAndExit; + + foreach( QString ar, args ) { + if ( ar.split('=').size() == 2 ) + argPairs.insert(ar.split('=').at(0), ar.split('=').at(1)); + else { + if ( ar == "--help" ) + goto LPrintHelpAndExit; + } + } + + role = argPairs.value("--role", "host"); + if ( role == "host" ) { +#if defined(Q_OS_WIN32) || defined(Q_OS_WINCE) + serPort = argPairs.value("--serport", "com3"); +#else + serPort = argPairs.value("--serport", "/dev/ttyS0"); +#endif + tcpPort = argPairs.value("--tcpport", "8756"); + } + else if ( role == "proxy" ) { + remoteHost = argPairs.value("--remotehost", "localhost"); + tcpPort = argPairs.value("--tcpport", "8756"); + } + else { + // invalid role + std::cout << "Invalid role specified." << std::endl; + goto LPrintHelpAndExit; + } + + return true; + +LPrintHelpAndExit: + printHelp(); + return false; +} + +int main(int argc, char *argv[]) +{ + QString role; + QString serPort; + QString tcpPort; + QString remoteHost; + QCoreApplication a(argc, argv); + + std::cout << "Serial port to TCP Bridge example, Copyright (c) 2010 Inbiza Systems Inc." << std::endl; + std::cout << "Created by Inbiza Labs " << std::endl; + + if ( !processArgs(a.arguments(), role, serPort, tcpPort, remoteHost) ) + return 0; + + Host *host; + Proxy *proxy; + + if ( role == "host" ) { + qDebug() << "role:" << role << "serport:" << serPort << "tcpport:" << tcpPort; + + host = new Host(serPort, tcpPort.toInt(), &a); + host->start(); + } + else { + qDebug() << "role:" << role << "remotehost:" << remoteHost << "tcpport:" << tcpPort; + + QHostAddress addr = (remoteHost == "localhost" ? QHostAddress::LocalHost : QHostAddress(remoteHost)); + + proxy = new Proxy(addr, tcpPort.toInt(), &a); + proxy->start(); + } + + return a.exec(); +} + diff --git a/thirdParty/qserialport/examples/serial2tcpbridge/process.cc b/thirdParty/qserialport/examples/serial2tcpbridge/process.cc new file mode 100644 index 0000000000000000000000000000000000000000..9233c0dfa256d2c5efa1c8c93ea0bd6b20f22d1a --- /dev/null +++ b/thirdParty/qserialport/examples/serial2tcpbridge/process.cc @@ -0,0 +1,622 @@ +// Copyright 2008 the V8 project authors. All rights reserved. +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Google Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +#include + +#include +#include + +using namespace std; +using namespace v8; + +// These interfaces represent an existing request processing interface. +// The idea is to imagine a real application that uses these interfaces +// and then add scripting capabilities that allow you to interact with +// the objects through JavaScript. + +/** + * A simplified http request. + */ +class HttpRequest { + public: + virtual ~HttpRequest() { } + virtual const string& Path() = 0; + virtual const string& Referrer() = 0; + virtual const string& Host() = 0; + virtual const string& UserAgent() = 0; +}; + +/** + * The abstract superclass of http request processors. + */ +class HttpRequestProcessor { + public: + virtual ~HttpRequestProcessor() { } + + // Initialize this processor. The map contains options that control + // how requests should be processed. + virtual bool Initialize(map* options, + map* output) = 0; + + // Process a single request. + virtual bool Process(HttpRequest* req) = 0; + + static void Log(const char* event); +}; + +/** + * An http request processor that is scriptable using JavaScript. + */ +class JsHttpRequestProcessor : public HttpRequestProcessor { + public: + + // Creates a new processor that processes requests by invoking the + // Process function of the JavaScript script given as an argument. + explicit JsHttpRequestProcessor(Handle script) : script_(script) { } + virtual ~JsHttpRequestProcessor(); + + virtual bool Initialize(map* opts, + map* output); + virtual bool Process(HttpRequest* req); + + private: + + // Execute the script associated with this processor and extract the + // Process function. Returns true if this succeeded, otherwise false. + bool ExecuteScript(Handle script); + + // Wrap the options and output map in a JavaScript objects and + // install it in the global namespace as 'options' and 'output'. + bool InstallMaps(map* opts, map* output); + + // Constructs the template that describes the JavaScript wrapper + // type for requests. + static Handle MakeRequestTemplate(); + static Handle MakeMapTemplate(); + + // Callbacks that access the individual fields of request objects. + static Handle GetPath(Local name, const AccessorInfo& info); + static Handle GetReferrer(Local name, + const AccessorInfo& info); + static Handle GetHost(Local name, const AccessorInfo& info); + static Handle GetUserAgent(Local name, + const AccessorInfo& info); + + // Callbacks that access maps + static Handle MapGet(Local name, const AccessorInfo& info); + static Handle MapSet(Local name, + Local value, + const AccessorInfo& info); + + // Utility methods for wrapping C++ objects as JavaScript objects, + // and going back again. + static Handle WrapMap(map* obj); + static map* UnwrapMap(Handle obj); + static Handle WrapRequest(HttpRequest* obj); + static HttpRequest* UnwrapRequest(Handle obj); + + Handle script_; + Persistent context_; + Persistent process_; + static Persistent request_template_; + static Persistent map_template_; +}; + +// ------------------------- +// --- P r o c e s s o r --- +// ------------------------- + + +static Handle LogCallback(const Arguments& args) { + if (args.Length() < 1) return v8::Undefined(); + HandleScope scope; + Handle arg = args[0]; + String::Utf8Value value(arg); + HttpRequestProcessor::Log(*value); + return v8::Undefined(); +} + + +// Execute the script and fetch the Process method. +bool JsHttpRequestProcessor::Initialize(map* opts, + map* output) { + // Create a handle scope to hold the temporary references. + HandleScope handle_scope; + + // Create a template for the global object where we set the + // built-in global functions. + Handle global = ObjectTemplate::New(); + global->Set(String::New("log"), FunctionTemplate::New(LogCallback)); + + // Each processor gets its own context so different processors + // don't affect each other (ignore the first three lines). + Handle context = Context::New(NULL, global); + + // Store the context in the processor object in a persistent handle, + // since we want the reference to remain after we return from this + // method. + context_ = Persistent::New(context); + + // Enter the new context so all the following operations take place + // within it. + Context::Scope context_scope(context); + + // Make the options mapping available within the context + if (!InstallMaps(opts, output)) + return false; + + // Compile and run the script + if (!ExecuteScript(script_)) + return false; + + // The script compiled and ran correctly. Now we fetch out the + // Process function from the global object. + Handle process_name = String::New("Process"); + Handle process_val = context->Global()->Get(process_name); + + // If there is no Process function, or if it is not a function, + // bail out + if (!process_val->IsFunction()) return false; + + // It is a function; cast it to a Function + Handle process_fun = Handle::Cast(process_val); + + // Store the function in a Persistent handle, since we also want + // that to remain after this call returns + process_ = Persistent::New(process_fun); + + // All done; all went well + return true; +} + + +bool JsHttpRequestProcessor::ExecuteScript(Handle script) { + HandleScope handle_scope; + + // We're just about to compile the script; set up an error handler to + // catch any exceptions the script might throw. + TryCatch try_catch; + + // Compile the script and check for errors. + Handle