/*===================================================================== PIXHAWK Micro Air Vehicle Flying Robotics Toolkit (c) 2009, 2010 PIXHAWK PROJECT This file is part of the PIXHAWK project PIXHAWK 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. PIXHAWK 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 PIXHAWK. If not, see . ======================================================================*/ /** * @file * @brief Definition of simulated system link * * @author Lorenz Meier * */ #ifndef MAVLINKSIMULATIONLINK_H #define MAVLINKSIMULATIONLINK_H #include #include #include #include #include #include #include #include "LinkInterface.h" class MAVLinkSimulationLink : public LinkInterface { Q_OBJECT public: MAVLinkSimulationLink(QString readFile="", QString writeFile="", int rate=5); ~MAVLinkSimulationLink(); bool isConnected(); qint64 bytesAvailable(); void run(); bool connect(); bool disconnect(); /* Extensive statistics for scientific purposes */ qint64 getNominalDataRate(); qint64 getTotalUpstream(); qint64 getShortTermUpstream(); qint64 getCurrentUpstream(); qint64 getMaxUpstream(); qint64 getTotalDownstream(); qint64 getShortTermDownstream(); qint64 getCurrentDownstream(); qint64 getMaxDownstream(); qint64 getBitsSent(); qint64 getBitsReceived(); QString getName(); int getId(); int getBaudRate(); int getBaudRateType(); int getFlowType(); int getParityType(); int getDataBitsType(); int getStopBitsType(); int getLinkQuality(); bool isFullDuplex(); public slots: void writeBytes(const char* data, qint64 size); void readBytes(char* const data, qint64 maxLength); void mainloop(); protected: // UAS properties float roll, pitch, yaw; int battery; QTimer* timer; /** File which contains the input data (simulated robot messages) **/ QFile* simulationFile; QString simulationHeader; /** File where the commands sent by the groundstation are stored **/ QFile* receiveFile; QTextStream stream; QTextStream* fileStream; QTextStream* outStream; /** Buffer which can be read from connected protocols through readBytes(). **/ QMutex readyBufferMutex; bool _isConnected; quint64 rate; int maxTimeNoise; quint64 lastSent; int readyBytes; QQueue readyBuffer; int id; QString name; qint64 timeOffset; sys_status_t status; void setMaximumTimeNoise(int milliseconds); void addTimeNoise(); void enqueue(uint8_t* stream, uint8_t* index, mavlink_message_t* msg); signals: void valueChanged(int uasId, QString curve, double value, quint64 usec); }; #endif // MAVLINKSIMULATIONLINK_H