Commit 8a6998d1 authored by Lorenz Meier's avatar Lorenz Meier

Hil tests

parent 73522dd1
......@@ -42,6 +42,7 @@ This file is part of the QGROUNDCONTROL project
QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) :
process(NULL),
terraSync(NULL),
socket(NULL),
startupArguments(startupArguments),
flightGearVersion(0)
{
......
......@@ -99,6 +99,11 @@ public slots:
Q_UNUSED(version);
}
void selectAirframe(const QString& airframe)
{
Q_UNUSED(airframe);
}
void readBytes();
/**
* @brief Write a number of bytes to the interface.
......
......@@ -48,6 +48,8 @@ public slots:
/** @brief Set the simulator version as text string */
virtual void setVersion(const QString& version) = 0;
virtual void selectAirframe(const QString& airframe) = 0;
virtual void readBytes() = 0;
/**
* @brief Write a number of bytes to the interface.
......
......@@ -75,7 +75,7 @@ void QGCXPlaneLink::loadSettings()
settings.beginGroup("QGC_XPLANE_LINK");
setRemoteHost(settings.value("REMOTE_HOST", QString("%1:%2").arg(remoteHost.toString()).arg(remotePort)).toString());
setVersion(settings.value("XPLANE_VERSION", 10).toInt());
selectPlane(settings.value("AIRFRAME", "default").toString());
selectAirframe(settings.value("AIRFRAME", "default").toString());
settings.endGroup();
}
......@@ -182,7 +182,6 @@ void QGCXPlaneLink::setRemoteHost(const QString& newHost)
if (newHost.contains(":"))
{
//qDebug() << "HOST: " << newHost.split(":").first();
QHostInfo info = QHostInfo::fromName(newHost.split(":").first());
if (info.error() == QHostInfo::NoError)
{
......@@ -198,7 +197,6 @@ void QGCXPlaneLink::setRemoteHost(const QString& newHost)
}
}
remoteHost = address;
//qDebug() << "Address:" << address.toString();
// Set localPort according to user input
remotePort = newHost.split(":").last().toInt();
}
......@@ -586,7 +584,7 @@ bool QGCXPlaneLink::disconnectSimulation()
return !connectState;
}
void QGCXPlaneLink::selectPlane(const QString& plane)
void QGCXPlaneLink::selectAirframe(const QString& plane)
{
airframeName = plane;
......@@ -718,6 +716,8 @@ void QGCXPlaneLink::setRandomAttitude()
bool QGCXPlaneLink::connectSimulation()
{
qDebug() << "STARTING X-PLANE LINK, CONNECTING TO" << remoteHost << ":" << remotePort;
// XXX Hack
storeSettings();
start(LowPriority);
......@@ -730,9 +730,6 @@ bool QGCXPlaneLink::connectSimulation()
QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes()));
//process = new QProcess(this);
//terraSync = new QProcess(this);
connect(mav, SIGNAL(hilControlsChanged(uint64_t, float, float, float, float, uint8_t, uint8_t)), this, SLOT(updateControls(uint64_t,float,float,float,float,uint8_t,uint8_t)));
connect(mav, SIGNAL(hilActuatorsChanged(uint64_t, float, float, float, float, float, float, float, float)), this, SLOT(updateActuators(uint64_t,float,float,float,float,float,float,float,float)));
connect(this, SIGNAL(hilStateChanged(uint64_t,float,float,float,float,float,float,int32_t,int32_t,int32_t,int16_t,int16_t,int16_t,int16_t,int16_t,int16_t)), mav, SLOT(sendHilState(uint64_t,float,float,float,float,float,float,int32_t,int32_t,int32_t,int16_t,int16_t,int16_t,int16_t,int16_t,int16_t)));
......
......@@ -130,7 +130,7 @@ public slots:
* @brief Select airplane model
* @param plane the name of the airplane
*/
void selectPlane(const QString& plane);
void selectAirframe(const QString& airframe);
/**
* @brief Set the airplane position and attitude
* @param lat
......
......@@ -97,7 +97,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
paramManager(NULL),
attitudeStamped(false),
lastAttitude(0),
simulation(new QGCXPlaneLink(this)),
simulation(0),
isLocalPositionKnown(false),
isGlobalPositionKnown(false),
systemIsArmed(false),
......@@ -2592,10 +2592,18 @@ bool UAS::emergencyKILL()
*/
void UAS::enableHilFlightGear(bool enable, QString options)
{
QGCFlightGearLink* link = dynamic_cast<QGCFlightGearLink*>(simulation);
if (!link || !simulation) {
// Delete wrong sim
if (simulation) {
stopHil();
delete simulation;
}
simulation = new QGCFlightGearLink(this, options);
}
// Connect Flight Gear Link
if (enable)
{
simulation = new QGCFlightGearLink(this, options);
startHil();
}
else
......@@ -2609,10 +2617,18 @@ void UAS::enableHilFlightGear(bool enable, QString options)
*/
void UAS::enableHilXPlane(bool enable)
{
QGCXPlaneLink* link = dynamic_cast<QGCXPlaneLink*>(simulation);
if (!link || !simulation) {
if (simulation) {
stopHil();
delete simulation;
}
qDebug() << "CREATED NEW XPLANE LINK";
simulation = new QGCXPlaneLink(this);
}
// Connect X-Plane Link
if (enable)
{
simulation = new QGCXPlaneLink(this);
startHil();
}
else
......@@ -2680,7 +2696,7 @@ void UAS::startHil()
*/
void UAS::stopHil()
{
simulation->disconnectSimulation();
if (simulation) simulation->disconnectSimulation();
mavlink_message_t msg;
mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
sendMessage(msg);
......
......@@ -10,12 +10,6 @@ QGCHilConfiguration::QGCHilConfiguration(UAS *mav, QWidget *parent) :
ui(new Ui::QGCHilConfiguration)
{
ui->setupUi(this);
connect(mav->getHILSimulation(), SIGNAL(statusMessage(QString)), this, SLOT(receiveStatusMessage(QString)));
connect(ui->simComboBox, SIGNAL(activated(QString)), mav->getHILSimulation(), SLOT(setVersion(QString)));
//ui->simComboBox->setEditText(mav->getHILSimulation()->getVersion());
// connect(ui->)
}
void QGCHilConfiguration::receiveStatusMessage(const QString& message)
......@@ -30,9 +24,10 @@ QGCHilConfiguration::~QGCHilConfiguration()
void QGCHilConfiguration::on_simComboBox_currentIndexChanged(int index)
{
//XXX make sure here that no other simulator is running
if(1 == index)
{
// Ensure the sim exists and is disabled
mav->enableHilFlightGear(false, "");
QGCHilFlightGearConfiguration* hfgconf = new QGCHilFlightGearConfiguration(mav, this);
hfgconf->show();
ui->simulatorConfigurationDockWidget->setWidget(hfgconf);
......@@ -40,6 +35,8 @@ void QGCHilConfiguration::on_simComboBox_currentIndexChanged(int index)
}
else if(2 == index || 3 == index)
{
// Ensure the sim exists and is disabled
mav->enableHilXPlane(false);
QGCHilXPlaneConfiguration* hxpconf = new QGCHilXPlaneConfiguration(mav->getHILSimulation(), this);
hxpconf->show();
ui->simulatorConfigurationDockWidget->setWidget(hxpconf);
......
......@@ -7,11 +7,15 @@ QGCHilXPlaneConfiguration::QGCHilXPlaneConfiguration(QGCHilLink* link, QWidget *
ui(new Ui::QGCHilXPlaneConfiguration)
{
ui->setupUi(this);
this->link = link;
connect(ui->startButton, SIGNAL(clicked(bool)), this, SLOT(toggleSimulation(bool)));
connect(ui->hostComboBox, SIGNAL(activated(QString)), link, SLOT(setRemoteHost(QString)));
connect(link, SIGNAL(remoteChanged(QString)), ui->hostComboBox, SLOT(setEditText(QString)));
connect(link, SIGNAL(statusMessage(QString)), this, SLOT(receiveStatusMessage(QString)));
connect(link, SIGNAL(statusMessage(QString)), parent, SLOT(receiveStatusMessage(QString)));
// connect(mav->getHILSimulation(), SIGNAL(statusMessage(QString)), this, SLOT(receiveStatusMessage(QString)));
// connect(ui->simComboBox, SIGNAL(activated(QString)), mav->getHILSimulation(), SLOT(setVersion(QString)));
ui->startButton->setText(tr("Connect"));
......@@ -21,7 +25,7 @@ QGCHilXPlaneConfiguration::QGCHilXPlaneConfiguration(QGCHilLink* link, QWidget *
{
connect(ui->randomAttitudeButton, SIGNAL(clicked()), link, SLOT(setRandomAttitude()));
connect(ui->randomPositionButton, SIGNAL(clicked()), link, SLOT(setRandomPosition()));
connect(ui->airframeComboBox, SIGNAL(activated(QString)), link, SLOT(setAirframe(QString)));
connect(ui->airframeComboBox, SIGNAL(activated(QString)), link, SLOT(selectAirframe(QString)));
ui->airframeComboBox->setCurrentIndex(link->getAirFrameIndex());
}
......
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