Commit 84e92285 authored by Don Gagne's avatar Don Gagne

Remove dead code

parent 621e754b
......@@ -221,19 +221,6 @@ void QGCFlightGearLink::setRemoteHost(const QString& host)
}
void QGCFlightGearLink::updateActuators(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8)
{
Q_UNUSED(time);
Q_UNUSED(act1);
Q_UNUSED(act2);
Q_UNUSED(act3);
Q_UNUSED(act4);
Q_UNUSED(act5);
Q_UNUSED(act6);
Q_UNUSED(act7);
Q_UNUSED(act8);
}
void QGCFlightGearLink::updateControls(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode)
{
// magnetos,aileron,elevator,rudder,throttle\n
......
......@@ -103,7 +103,6 @@ public slots:
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);
void updateActuators(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
/** @brief Set the simulator version as text string */
void setVersion(const QString& version)
{
......
......@@ -49,7 +49,6 @@ public slots:
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 updateActuators(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8) = 0;
virtual void processError(QProcess::ProcessError err) = 0;
/** @brief Set the simulator version as text string */
virtual void setVersion(const QString& version) = 0;
......
......@@ -233,19 +233,6 @@ void QGCJSBSimLink::setRemoteHost(const QString& host)
}
void QGCJSBSimLink::updateActuators(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8)
{
Q_UNUSED(time);
Q_UNUSED(act1);
Q_UNUSED(act2);
Q_UNUSED(act3);
Q_UNUSED(act4);
Q_UNUSED(act5);
Q_UNUSED(act6);
Q_UNUSED(act7);
Q_UNUSED(act8);
}
void QGCJSBSimLink::updateControls(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode)
{
// magnetos,aileron,elevator,rudder,throttle\n
......
......@@ -92,7 +92,6 @@ public slots:
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);
void updateActuators(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
// /** @brief Remove a host from broadcasting messages to */
// void removeHost(const QString& host);
// void readPendingDatagrams();
......
......@@ -183,7 +183,6 @@ void QGCXPlaneLink::run()
QObject::connect(socket, &QUdpSocket::readyRead, this, &QGCXPlaneLink::readBytes);
connect(_vehicle->uas(), &UAS::hilControlsChanged, this, &QGCXPlaneLink::updateControls, Qt::QueuedConnection);
connect(_vehicle->uas(), &UAS::hilActuatorsChanged, this, &QGCXPlaneLink::updateActuators, Qt::QueuedConnection);
connect(this, &QGCXPlaneLink::hilGroundTruthChanged, _vehicle->uas(), &UAS::sendHilGroundTruth, Qt::QueuedConnection);
connect(this, &QGCXPlaneLink::hilStateChanged, _vehicle->uas(), &UAS::sendHilState, Qt::QueuedConnection);
......@@ -240,7 +239,6 @@ void QGCXPlaneLink::run()
}
disconnect(_vehicle->uas(), &UAS::hilControlsChanged, this, &QGCXPlaneLink::updateControls);
disconnect(_vehicle->uas(), &UAS::hilActuatorsChanged, this, &QGCXPlaneLink::updateActuators);
disconnect(this, &QGCXPlaneLink::hilGroundTruthChanged, _vehicle->uas(), &UAS::sendHilGroundTruth);
disconnect(this, &QGCXPlaneLink::hilStateChanged, _vehicle->uas(), &UAS::sendHilState);
......@@ -351,68 +349,6 @@ void QGCXPlaneLink::setRemoteHost(const QString& newHost)
emit remoteChanged(QString("%1:%2").arg(remoteHost.toString()).arg(remotePort));
}
void QGCXPlaneLink::updateActuators(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8)
{
if (_vehicle->vehicleType() == MAV_TYPE_QUADROTOR)
// Only update this for multirotors
{
Q_UNUSED(time);
Q_UNUSED(act5);
Q_UNUSED(act6);
Q_UNUSED(act7);
Q_UNUSED(act8);
#pragma pack(push, 1)
struct payload {
char b[5];
int index;
float f[8];
} p;
#pragma pack(pop)
p.b[0] = 'D';
p.b[1] = 'A';
p.b[2] = 'T';
p.b[3] = 'A';
p.b[4] = '\0';
p.index = 25;
memset(p.f, 0, sizeof(p.f));
p.f[0] = act1;
p.f[1] = act2;
p.f[2] = act3;
p.f[3] = act4;
// XXX the system corrects for the scale onboard, do not scale again
// if (airframeID == AIRFRAME_QUAD_X_MK_10INCH_I2C)
// {
// p.f[0] = act1 / 255.0f;
// p.f[1] = act2 / 255.0f;
// p.f[2] = act3 / 255.0f;
// p.f[3] = act4 / 255.0f;
// }
// else if (airframeID == AIRFRAME_QUAD_X_ARDRONE)
// {
// p.f[0] = act1 / 500.0f;
// p.f[1] = act2 / 500.0f;
// p.f[2] = act3 / 500.0f;
// p.f[3] = act4 / 500.0f;
// }
// else
// {
// p.f[0] = (act1 - 1000.0f) / 1000.0f;
// p.f[1] = (act2 - 1000.0f) / 1000.0f;
// p.f[2] = (act3 - 1000.0f) / 1000.0f;
// p.f[3] = (act4 - 1000.0f) / 1000.0f;
// }
// Throttle
writeBytes((const char*)&p, sizeof(p));
}
}
void QGCXPlaneLink::updateControls(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode)
{
#pragma pack(push, 1)
......
......@@ -112,8 +112,6 @@ public slots:
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 motor control states to the simulation */
void updateActuators(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
/** @brief Set the simulator version as text string */
void setVersion(const QString& version);
/** @brief Set the simulator version as integer */
......
......@@ -614,8 +614,6 @@ signals:
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);
/** @brief HIL actuator outputs have changed */
void hilActuatorsChanged(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
void localXChanged(double val,QString name);
void localYChanged(double val,QString name);
......
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