/*===================================================================== QGroundControl Open Source Ground Control Station (c) 2009, 2010 QGROUNDCONTROL PROJECT This file is part of the QGROUNDCONTROL project QGROUNDCONTROL is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. QGROUNDCONTROL 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 General Public License along with QGROUNDCONTROL. If not, see . ======================================================================*/ /** * @file * @brief Connection to OpalRT * @author Bryan Godbolt */ #ifndef OPALLINK_H #define OPALLINK_H #include #include #include #include #include #include #include #include #include #include "LinkInterface.h" #include "LinkManager.h" #include "MG.h" #include "mavlink.h" #include "mavlink_types.h" #include "configuration.h" #include "OpalRT.h" #include "ParameterList.h" #include "errno.h" #ifdef OPAL_RT #include "OpalApi.h" #endif #include "string.h" /* Configuration info for the model */ #define NUM_OUTPUT_SIGNALS 36 /** * @brief Interface to OpalRT targets * * This is an interface to the OpalRT hardware-in-the-loop (HIL) simulator. * This class receives MAVLink packets as if it is a true link, but it * interprets the packets internally, and calls the appropriate api functions. * * @author Bryan Godbolt * @ref http://www.opal-rt.com/ */ class OpalLink : public LinkInterface { Q_OBJECT public: OpalLink(); /* Connection management */ int getId(); QString getName(); bool isConnected(); /* Connection characteristics */ qint64 getNominalDataRate(); bool isFullDuplex(); int getLinkQuality(); qint64 getTotalUpstream(); qint64 getTotalDownstream(); qint64 getCurrentUpstream(); qint64 getMaxUpstream(); qint64 getBitsSent(); qint64 getBitsReceived(); bool connect(); bool disconnect(); qint64 bytesAvailable(); void run(); static void setLastErrorMsg(); static void displayLastErrorMsg(); public slots: void writeBytes(const char *bytes, qint64 length); void readBytes(); void heartbeat(); void getSignals(); protected slots: void receiveMessage(mavlink_message_t message); void setSignals(double *values); protected: QString name; int id; bool connectState; quint64 bitsSentTotal; quint64 bitsSentCurrent; quint64 bitsSentMax; quint64 bitsReceivedTotal; quint64 bitsReceivedCurrent; quint64 bitsReceivedMax; quint64 connectionStartTime; QMutex statisticsMutex; QMutex receiveDataMutex; // QMutex getSignalsMutex; static QString lastErrorMsg; void setName(QString name); QTimer* heartbeatTimer; ///< Timer to emit heartbeats int heartbeatRate; ///< Heartbeat rate, controls the timer interval bool m_heartbeatsEnabled; ///< Enabled/disable heartbeat emission QTimer* getSignalsTimer; int getSignalsPeriod; QQueue* receiveBuffer; QByteArray* sendBuffer; const int systemID; const int componentID; void getParameterList(); OpalRT::ParameterList *params; }; //QString OpalLink::lastErrorMsg = QString(); #endif // OPALLINK_H