Newer
Older
Michael Carpenter
committed
void satelliteCountChanged(double val,QString name);
Michael Carpenter
committed
void distToWaypointChanged(double val,QString name);
void groundSpeedChanged(double val, QString name);
Anton Babushkin
committed
void airSpeedChanged(double val, QString name);
void bearingToWaypointChanged(double val,QString name);
protected:
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
quint64 getUnixTime(quint64 time=0);
/** @brief Get the UNIX timestamp in milliseconds, enter milliseconds */
quint64 getUnixTimeFromMs(quint64 time);
/** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
quint64 getUnixReferenceTime(quint64 time);
virtual void processParamValueMsg(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue);
virtual void processParamValueMsgHook(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue) { Q_UNUSED(msg); Q_UNUSED(paramName); Q_UNUSED(rawValue); Q_UNUSED(paramValue); };
int componentID[256];
bool componentMulti[256];
bool connectionLost; ///< Flag indicates a timed out connection
quint64 connectionLossTime; ///< Time the connection was interrupted
quint64 lastVoltageWarning; ///< Time at which the last voltage warning occured
quint64 lastNonNullTime; ///< The last timestamp from the MAV that was not null
unsigned int onboardTimeOffsetInvalidCount; ///< Count when the offboard time offset estimation seemed wrong
bool hilEnabled; ///< Set to true if HIL mode is enabled from GCS (UAS might be in HIL even if this flag is not set, this defines the GCS HIL setting)
bool sensorHil; ///< True if sensor HIL is enabled
quint64 lastSendTimeGPS; ///< Last HIL GPS message sent
quint64 lastSendTimeSensors; ///< Last HIL Sensors message sent
quint64 lastSendTimeOpticalFlow; ///< Last HIL Optical Flow message sent
QList<QAction*> actions; ///< A list of actions that this UAS can perform.
protected slots:
/** @brief Write settings to disk */
void writeSettings();
/** @brief Read settings from disk */
void readSettings();
// // MESSAGE RECEPTION
// /** @brief Receive a named value message */
// void receiveMessageNamedValue(const mavlink_message_t& message);
private:
// unsigned int mode; ///< The current mode of the MAV
};
#endif // _UAS_H_