Unverified Commit e9bafe97 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8617 from DonLakeFlyer/RemoveHILCode

Remove unused HIL code
parents 6d059984 1396001f
......@@ -751,9 +751,6 @@ HEADERS += \
src/GPS/vehicle_gps_position.h \
src/Joystick/JoystickSDL.h \
src/RunGuard.h \
src/comm/QGCHilLink.h \
src/comm/QGCJSBSimLink.h \
src/comm/QGCXPlaneLink.h \
}
iOSBuild {
......@@ -940,8 +937,6 @@ SOURCES += \
src/GPS/RTCM/RTCMMavlink.cc \
src/Joystick/JoystickSDL.cc \
src/RunGuard.cc \
src/comm/QGCJSBSimLink.cc \
src/comm/QGCXPlaneLink.cc \
}
#
......
......@@ -66,11 +66,9 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
_airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
if (!_vehicle->hilMode()) {
_sensorsComponent = new SensorsComponent(_vehicle, this);
_sensorsComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_sensorsComponent));
}
_sensorsComponent = new SensorsComponent(_vehicle, this);
_sensorsComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_sensorsComponent));
_radioComponent = new PX4RadioComponent(_vehicle, this);
_radioComponent->setupTriggerSignals();
......@@ -151,7 +149,7 @@ QString PX4AutoPilotPlugin::prerequisiteSetup(VehicleComponent* component) const
return _airframeComponent->name();
} else if (_radioComponent && !_radioComponent->setupComplete()) {
return _radioComponent->name();
} else if (_sensorsComponent && !_vehicle->hilMode() && !_sensorsComponent->setupComplete()) {
} else if (_sensorsComponent && !_sensorsComponent->setupComplete()) {
return _sensorsComponent->name();
}
}
......
......@@ -788,9 +788,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_WIND_COV:
_handleWindCov(message);
break;
case MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS:
_handleHilActuatorControls(message);
break;
case MAVLINK_MSG_ID_LOGGING_DATA:
_handleMavlinkLoggingData(message);
break;
......@@ -1451,30 +1448,6 @@ QString Vehicle::vehicleUIDStr()
return uid;
}
void Vehicle::_handleHilActuatorControls(mavlink_message_t &message)
{
mavlink_hil_actuator_controls_t hil;
mavlink_msg_hil_actuator_controls_decode(&message, &hil);
emit hilActuatorControlsChanged(hil.time_usec, hil.flags,
hil.controls[0],
hil.controls[1],
hil.controls[2],
hil.controls[3],
hil.controls[4],
hil.controls[5],
hil.controls[6],
hil.controls[7],
hil.controls[8],
hil.controls[9],
hil.controls[10],
hil.controls[11],
hil.controls[12],
hil.controls[13],
hil.controls[14],
hil.controls[15],
hil.mode);
}
void Vehicle::_handleCommandLong(mavlink_message_t& message)
{
#ifdef NO_SERIAL_LINK
......@@ -2526,30 +2499,6 @@ void Vehicle::setPriorityLinkByName(const QString& priorityLinkName)
}
}
bool Vehicle::hilMode()
{
return _base_mode & MAV_MODE_FLAG_HIL_ENABLED;
}
void Vehicle::setHilMode(bool hilMode)
{
mavlink_message_t msg;
uint8_t newBaseMode = _base_mode & ~MAV_MODE_FLAG_DECODE_POSITION_HIL;
if (hilMode) {
newBaseMode |= MAV_MODE_FLAG_HIL_ENABLED;
}
mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
id(),
newBaseMode,
_custom_mode);
sendMessageOnLink(priorityLink(), msg);
}
void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple)
{
mavlink_message_t msg;
......
......@@ -543,7 +543,6 @@ public:
Q_PROPERTY(QStringList flightModes READ flightModes NOTIFY flightModesChanged)
Q_PROPERTY(QStringList extraJoystickFlightModes READ extraJoystickFlightModes NOTIFY flightModesChanged)
Q_PROPERTY(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged)
Q_PROPERTY(bool hilMode READ hilMode WRITE setHilMode NOTIFY hilModeChanged)
Q_PROPERTY(TrajectoryPoints* trajectoryPoints MEMBER _trajectoryPoints CONSTANT)
Q_PROPERTY(QmlObjectListModel* cameraTriggerPoints READ cameraTriggerPoints CONSTANT)
Q_PROPERTY(float latitude READ latitude NOTIFY coordinateChanged)
......@@ -866,9 +865,6 @@ public:
QVariantList links() const;
void setPriorityLinkByName(const QString& priorityLinkName);
bool hilMode();
void setHilMode(bool hilMode);
bool fixedWing() const;
bool multiRotor() const;
bool vtol() const;
......@@ -1135,9 +1131,6 @@ signals:
void armedPositionChanged();
void armedChanged (bool armed);
void flightModeChanged (const QString& flightMode);
void hilModeChanged (bool hilMode);
/** @brief HIL actuator controls (replaces HIL controls) */
void hilActuatorControlsChanged (quint64 time, quint64 flags, float ctl_0, float ctl_1, float ctl_2, float ctl_3, float ctl_4, float ctl_5, float ctl_6, float ctl_7, float ctl_8, float ctl_9, float ctl_10, float ctl_11, float ctl_12, float ctl_13, float ctl_14, float ctl_15, quint8 mode);
void connectionLostChanged (bool connectionLost);
void connectionLostEnabledChanged (bool connectionLostEnabled);
void autoDisconnectChanged (bool autoDisconnectChanged);
......@@ -1299,7 +1292,6 @@ private:
void _handleCommandLong (mavlink_message_t& message);
void _handleAutopilotVersion (LinkInterface* link, mavlink_message_t& message);
void _handleProtocolVersion (LinkInterface* link, mavlink_message_t& message);
void _handleHilActuatorControls (mavlink_message_t& message);
void _handleGpsRawInt (mavlink_message_t& message);
void _handleGlobalPositionInt (mavlink_message_t& message);
void _handleAltitude (mavlink_message_t& message);
......
#pragma once
#include <QThread>
#include <QProcess>
#include "inttypes.h"
class QGCHilLink : public QThread
{
Q_OBJECT
public:
virtual bool isConnected() = 0;
virtual qint64 bytesAvailable() = 0;
virtual int getPort() const = 0;
/**
* @brief The human readable port name
*/
virtual QString getName() = 0;
/**
* @brief Get remote host and port
* @return string in format <host>:<port>
*/
virtual QString getRemoteHost() = 0;
/**
* @brief Get the application name and version
* @return A string containing a unique application name and compatibility version
*/
virtual QString getVersion() = 0;
/**
* @brief Get index of currently selected airframe
* @return -1 if default is selected, index else
*/
virtual int getAirFrameIndex() = 0;
/**
* @brief Check if sensor level HIL is enabled
* @return true if sensor HIL is enabled
*/
virtual bool sensorHilEnabled() = 0;
public slots:
virtual void setPort(int port) = 0;
/** @brief Add a new host to broadcast messages to */
virtual void setRemoteHost(const QString& host) = 0;
/** @brief Send new control states to the simulation */
virtual void updateControls(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode) = 0;
virtual void processError(QProcess::ProcessError err) = 0;
/** @brief Set the simulator version as text string */
virtual void setVersion(const QString& version) = 0;
/** @brief Enable sensor-level HIL (instead of state-level HIL) */
virtual void enableSensorHIL(bool enable) = 0;
virtual void selectAirframe(const QString& airframe) = 0;
virtual void readBytes() = 0;
/**
* @brief Write a number of bytes to the interface.
*
* @param data Pointer to the data byte array
* @param size The size of the bytes array
**/
void writeBytesSafe(const char* data, int length)
{
emit _invokeWriteBytes(QByteArray(data, length));
}
virtual bool connectSimulation() = 0;
virtual bool disconnectSimulation() = 0;
private slots:
virtual void _writeBytes(const QByteArray) = 0;
protected:
virtual void setName(QString name) = 0;
QGCHilLink() :
QThread()
{
connect(this, &QGCHilLink::_invokeWriteBytes, this, &QGCHilLink::_writeBytes);
}
signals:
/**
* @brief This signal is emitted instantly when the link is connected
**/
void simulationConnected();
/**
* @brief This signal is emitted instantly when the link is disconnected
**/
void simulationDisconnected();
/**
* @brief Thread safe signal to disconnect simulator from other threads
**/
void disconnectSim();
/**
* @brief This signal is emitted instantly when the link status changes
**/
void simulationConnected(bool connected);
/** @brief State update from simulation */
void hilStateChanged(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
float pitchspeed, float yawspeed, double lat, double lon, double alt,
float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc);
void hilGroundTruthChanged(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
float pitchspeed, float yawspeed, double lat, double lon, double alt,
float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc);
void sensorHilGpsChanged(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites);
void sensorHilRawImuChanged(quint64 time_us, float xacc, float yacc, float zacc,
float xgyro, float ygyro, float zgyro,
float xmag, float ymag, float zmag,
float abs_pressure, float diff_pressure,
float pressure_alt, float temperature,
quint32 fields_updated);
void sensorHilOpticalFlowChanged(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
float flow_comp_m_y, quint8 quality, float ground_distance);
/** @brief Remote host and port changed */
void remoteChanged(const QString& hostPort);
/** @brief Status text message from link */
void statusMessage(const QString& message);
/** @brief Airframe changed */
void airframeChanged(const QString& airframe);
/** @brief Selected sim version changed */
void versionChanged(const QString& version);
/** @brief Selected sim version changed */
void versionChanged(const int version);
/** @brief Sensor leve HIL state changed */
void sensorHilChanged(bool enabled);
/** @brief Helper signal to force execution on the correct thread */
void _invokeWriteBytes(QByteArray);
};
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
/**
* @file
* @brief UDP connection (server) for unmanned vehicles
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#pragma once
#include <QString>
#include <QList>
#include <QMap>
#include <QMutex>
#include <QUdpSocket>
#include <QTimer>
#include <QProcess>
#include <LinkInterface.h>
#include "QGCConfig.h"
#include "QGCHilLink.h"
#include "Vehicle.h"
class QGCJSBSimLink : public QGCHilLink
{
Q_OBJECT
//Q_INTERFACES(QGCJSBSimLinkInterface:LinkInterface)
public:
QGCJSBSimLink(Vehicle* vehicle, QString startupArguments, QString remoteHost=QString("127.0.0.1:49000"), QHostAddress host = QHostAddress::Any, quint16 port = 49005);
~QGCJSBSimLink();
bool isConnected();
qint64 bytesAvailable();
int getPort() const {
return port;
}
/**
* @brief The human readable port name
*/
QString getName();
/**
* @brief Get remote host and port
* @return string in format <host>:<port>
*/
QString getRemoteHost();
QString getVersion()
{
return QString("FlightGear %1").arg(flightGearVersion);
}
int getAirFrameIndex()
{
return -1;
}
void run();
bool sensorHilEnabled() {
return _sensorHilEnabled;
}
public slots:
// void setAddress(QString address);
void setPort(int port);
/** @brief Add a new host to broadcast messages to */
void setRemoteHost(const QString& host);
/** @brief Send new control states to the simulation */
void updateControls(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode);
// /** @brief Remove a host from broadcasting messages to */
// void removeHost(const QString& host);
// void readPendingDatagrams();
void processError(QProcess::ProcessError err);
/** @brief Set the simulator version as text string */
void setVersion(const QString& version)
{
Q_UNUSED(version);
}
void selectAirframe(const QString& airframe)
{
script = airframe;
}
void enableSensorHIL(bool enable) {
if (enable != _sensorHilEnabled) {
_sensorHilEnabled = enable;
emit sensorHilChanged(enable);
}
}
void readBytes();
private slots:
/**
* @brief Write a number of bytes to the interface.
*
* @param data Pointer to the data byte array
* @param size The size of the bytes array
**/
void _writeBytes(const QByteArray data);
public slots:
bool connectSimulation();
bool disconnectSimulation();
void setStartupArguments(QString startupArguments);
private:
Vehicle* _vehicle;
QString name;
QHostAddress host;
QHostAddress currentHost;
quint16 currentPort;
quint16 port;
int id;
QUdpSocket* socket;
bool connectState;
quint64 bitsSentTotal;
quint64 bitsSentCurrent;
quint64 bitsSentMax;
quint64 bitsReceivedTotal;
quint64 bitsReceivedCurrent;
quint64 bitsReceivedMax;
quint64 connectionStartTime;
QMutex statisticsMutex;
QMutex dataMutex;
QTimer refreshTimer;
QProcess* process;
unsigned int flightGearVersion;
QString startupArguments;
QString script;
bool _sensorHilEnabled;
void setName(QString name);
};
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
/**
* @file QGCXPlaneLink.h
* @brief X-Plane simulation link
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#pragma once
#include <QString>
#include <QList>
#include <QMap>
#include <QMutex>
#include <QUdpSocket>
#include <QTimer>
#include <QProcess>
#include <LinkInterface.h>
#include "QGCConfig.h"
#include "QGCHilLink.h"
#include "Vehicle.h"
class QGCXPlaneLink : public QGCHilLink
{
Q_OBJECT
//Q_INTERFACES(QGCXPlaneLinkInterface:LinkInterface)
public:
QGCXPlaneLink(Vehicle* vehicle, QString remoteHost=QString("127.0.0.1:49000"), QHostAddress localHost = QHostAddress::Any, quint16 localPort = 49005);
~QGCXPlaneLink();
/**
* @brief Load X-Plane HIL settings
*/
void loadSettings();
/**
* @brief Store X-Plane HIL settings
*/
void storeSettings();
bool isConnected();
qint64 bytesAvailable();
int getPort() const {
return localPort;
}
/**
* @brief The human readable port name
*/
QString getName();
void run();
/**
* @brief Get remote host and port
* @return string in format <host>:<port>
*/
QString getRemoteHost();
enum AIRFRAME
{
AIRFRAME_UNKNOWN = 0,
AIRFRAME_QUAD_DJI_F450_PWM,
AIRFRAME_QUAD_X_MK_10INCH_I2C,
AIRFRAME_QUAD_X_ARDRONE,
AIRFRAME_FIXED_WING_BIXLER_II,
AIRFRAME_FIXED_WING_BIXLER_II_AILERONS
};
QString getVersion()
{
return QString("X-Plane %1").arg(xPlaneVersion);
}
int getAirFrameIndex()
{
return (int)airframeID;
}
bool sensorHilEnabled() {
return _sensorHilEnabled;
}
bool useHilActuatorControls() {
return _useHilActuatorControls;
}
signals:
/** @brief Sensor leve HIL state changed */
void useHilActuatorControlsChanged(bool enabled);
public slots:
// void setAddress(QString address);
void setPort(int port);
/** @brief Add a new host to broadcast messages to */
void setRemoteHost(const QString& host);
/** @brief Send new control states to the simulation */
void updateControls(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode);
/** @brief Send new control commands to the simulation */
void updateActuatorControls(quint64 time, quint64 flags,
float ctl_0,
float ctl_1,
float ctl_2,
float ctl_3,
float ctl_4,
float ctl_5,
float ctl_6,
float ctl_7,
float ctl_8,
float ctl_9,
float ctl_10,
float ctl_11,
float ctl_12,
float ctl_13,
float ctl_14,
float ctl_15,
quint8 mode);
/** @brief Set the simulator version as text string */
void setVersion(const QString& version);
/** @brief Set the simulator version as integer */
void setVersion(unsigned int version);
void enableSensorHIL(bool enable) {
if (enable != _sensorHilEnabled) {
_sensorHilEnabled = enable;
emit sensorHilChanged(enable);
}
}
void enableHilActuatorControls(bool enable);
void processError(QProcess::ProcessError err);
void readBytes();
private slots:
/**
* @brief Write a number of bytes to the interface.
*
* @param data Pointer to the data byte array
* @param size The size of the bytes array
**/
void _writeBytes(const QByteArray data);
public slots:
bool connectSimulation();
bool disconnectSimulation();
/**
* @brief Select airplane model
* @param plane the name of the airplane
*/
void selectAirframe(const QString& airframe);
/**
* @brief Set the airplane position and attitude
* @param lat
* @param lon
* @param alt
* @param roll
* @param pitch
* @param yaw
*/
void setPositionAttitude(double lat, double lon, double alt, double roll, double pitch, double yaw);
/**
* @brief Set a random position
*/
void setRandomPosition();
/**
* @brief Set a random attitude
*/
void setRandomAttitude();
protected:
Vehicle* _vehicle;
QString name;
QHostAddress localHost;
quint16 localPort;
QHostAddress remoteHost;
quint16 remotePort;
int id;
QUdpSocket* socket;
bool connectState;
quint64 bitsSentTotal;
quint64 bitsSentCurrent;
quint64 bitsSentMax;
quint64 bitsReceivedTotal;
quint64 bitsReceivedCurrent;
quint64 bitsReceivedMax;
quint64 connectionStartTime;
QMutex statisticsMutex;
QMutex dataMutex;
QTimer refreshTimer;
QProcess* process;
QProcess* terraSync;
bool gpsReceived;
bool attitudeReceived;
float roll, pitch, yaw, rollspeed, pitchspeed, yawspeed;
double lat, lon, alt, alt_agl;
float vx, vy, vz, xacc, yacc, zacc;
float ind_airspeed;
float true_airspeed;
float groundspeed;
float xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature;
float barometerOffsetkPa;
float man_roll, man_pitch, man_yaw;
QString airframeName;
enum AIRFRAME airframeID;
bool xPlaneConnected;
unsigned int xPlaneVersion;
quint64 simUpdateLast;
quint64 simUpdateFirst;
quint64 simUpdateLastText;
quint64 simUpdateLastGroundTruth;
float simUpdateHz;
bool _sensorHilEnabled;
bool _useHilActuatorControls;
bool _should_exit;
void setName(QString name);
void sendDataRef(QString ref, float value);
};
This diff is collapsed.
......@@ -22,9 +22,6 @@
#ifndef __mobile__
#include "FileManager.h"
#include "QGCHilLink.h"
#include "QGCJSBSimLink.h"
#include "QGCXPlaneLink.h"
#endif
Q_DECLARE_LOGGING_CATEGORY(UASLog)
......@@ -181,11 +178,6 @@ protected:
float pressure_alt_var; ///< variance of altitude pressure noise for HIL sim (hPa)
float temperature_var; ///< variance of temperature noise for HIL sim (C)
/// SIMULATION
#ifndef __mobile__
QGCHilLink* simulation; ///< Hardware in the loop simulation link
#endif
public:
/** @brief Get the human-readable status message for this code */
void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);
......@@ -194,13 +186,6 @@ public:
virtual FileManager* getFileManager() { return &fileManager; }
#endif
/** @brief Get the HIL simulation */
#ifndef __mobile__
QGCHilLink* getHILSimulation() const {
return simulation;
}
#endif
QImage getImage();
void requestImage();
......@@ -208,52 +193,6 @@ public slots:
/** @brief Order the robot to pair its receiver **/
void pairRX(int rxType, int rxSubType);
/** @brief Enable / disable HIL */
#ifndef __mobile__
void enableHilJSBSim(bool enable, QString options);
void enableHilXPlane(bool enable);
/** @brief Send the full HIL state to the MAV */
void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollRotationRate,
float pitchRotationRate, float yawRotationRate, double lat, double lon, double alt,
float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc);
void sendHilGroundTruth(quint64 time_us, float roll, float pitch, float yaw, float rollRotationRate,
float pitchRotationRate, float yawRotationRate, double lat, double lon, double alt,
float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc);
/** @brief RAW sensors for sensor HIL */
void sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, quint32 fields_changed);
/** @brief Send Optical Flow sensor message for HIL, (arguments and units accoding to mavlink documentation*/
void sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
float flow_comp_m_y, quint8 quality, float ground_distance);
float addZeroMeanNoise(float truth_meas, float noise_var);
/**
* @param time_us
* @param lat
* @param lon
* @param alt
* @param fix_type
* @param eph
* @param epv
* @param vel
* @param cog course over ground, in radians, -pi..pi
* @param satellites
*/
void sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites);
/** @brief Places the UAV in Hardware-in-the-Loop simulation status **/
void startHil();
/** @brief Stops the UAV's Hardware-in-the-Loop simulation status **/
void stopHil();
#endif
/** @brief Set the values for the manual control of the vehicle */
void setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode);
......@@ -280,8 +219,6 @@ signals:
void imageStarted(quint64 timestamp);
/** @brief A new camera image has arrived */
void imageReady(UASInterface* uas);
/** @brief HIL controls have changed */
void hilControlsChanged(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode);
void rollChanged(double val,QString name);
void pitchChanged(double val,QString name);
......@@ -305,11 +242,6 @@ protected:
quint64 lastVoltageWarning; ///< Time at which the last voltage warning occurred
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;
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
private:
Vehicle* _vehicle;
......
......@@ -82,24 +82,6 @@ public slots:
/** @brief Order the robot to pair its receiver **/
virtual void pairRX(int rxType, int rxSubType) = 0;
/** @brief Send the full HIL state to the MAV */
#ifndef __mobile__
virtual void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
float pitchspeed, float yawspeed, double lat, double lon, double alt,
float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc) = 0;
/** @brief RAW sensors for sensor HIL */
virtual void sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, quint32 fields_changed) = 0;
/** @brief Send raw GPS for sensor HIL */
virtual void sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites) = 0;
/** @brief Send Optical Flow sensor message for HIL, (arguments and units accoding to mavlink documentation*/
virtual void sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
float flow_comp_m_y, quint8 quality, float ground_distance) = 0;
#endif
/** @brief Send command to map a RC channel to a parameter */
virtual void sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax) = 0;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment