Commit 3131d7e5 authored by Lorenz Meier's avatar Lorenz Meier

Substantial cleanup in joystick interface, operational now

parent 31a1a070
......@@ -557,7 +557,7 @@ contains(DEPENDENCIES_PRESENT, osg) {
message("Including sources for osgEarth")
# Enable only if OpenSceneGraph is available
SOURCES += src/ui/map3D/QMap3D.cc
SOURCES +=
}
}
contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) {
......
......@@ -142,6 +142,11 @@ void QGCFlightGearLink::setRemoteHost(const QString& host)
}
void QGCFlightGearLink::updateActuators(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8)
{
}
void QGCFlightGearLink::updateControls(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode)
{
// magnetos,aileron,elevator,rudder,throttle\n
......
......@@ -78,6 +78,7 @@ public slots:
void setRemoteHost(const QString& host);
/** @brief Send new control states to the simulation */
void updateControls(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);
void updateActuators(uint64_t 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();
......
......@@ -31,6 +31,7 @@ public slots:
virtual void setRemoteHost(const QString& host) = 0;
/** @brief Send new control states to the simulation */
virtual void updateControls(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode) = 0;
virtual void updateActuators(uint64_t 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;
virtual void readBytes() = 0;
......@@ -68,6 +69,11 @@ signals:
float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt,
int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc);
/** @brief Remote host and port changed */
void remoteChanged(const QString& hostPort);
/** @brief Status text message from link */
void statusMessage(const QString& message);
};
#endif // QGCHILLINK_H
This diff is collapsed.
......@@ -81,6 +81,16 @@ public:
*/
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
};
public slots:
// void setAddress(QString address);
void setPort(int port);
......@@ -88,9 +98,8 @@ public slots:
void setRemoteHost(const QString& host);
/** @brief Send new control states to the simulation */
void updateControls(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);
// /** @brief Remove a host from broadcasting messages to */
// void removeHost(const QString& host);
// void readPendingDatagrams();
/** @brief Send new motor control states to the simulation */
void updateActuators(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
void processError(QProcess::ProcessError err);
void readBytes();
......@@ -163,6 +172,9 @@ protected:
float groundspeed;
float man_roll, man_pitch, man_yaw;
QString airframeName;
enum AIRFRAME airframeID;
bool xPlaneConnected;
void setName(QString name);
......
......@@ -214,19 +214,20 @@ void JoystickInput::run()
}
}
// Display all axes
for(int i = 0; i < SDL_JoystickNumAxes(joystick); i++)
{
//qDebug() << "\rAXIS" << i << "is: " << SDL_JoystickGetAxis(joystick, i);
}
// // Display all axes
// for(int i = 0; i < SDL_JoystickNumAxes(joystick); i++)
// {
// qDebug() << "\rAXIS" << i << "is: " << SDL_JoystickGetAxis(joystick, i);
// }
// THRUST
double thrust = ((double)SDL_JoystickGetAxis(joystick, thrustAxis) - calibrationNegative[thrustAxis]) / (calibrationPositive[thrustAxis] - calibrationNegative[thrustAxis]);
// Has to be inverted for Logitech Wingman
thrust = 1.0f - thrust;
thrust = thrust * 2.0f - 1.0f;
// Bound rounding errors
if (thrust > 1) thrust = 1;
if (thrust < 0) thrust = 0;
if (thrust > 1.0f) thrust = 1.0f;
if (thrust < -1.0f) thrust = -1.0f;
emit thrustChanged((float)thrust);
// X Axis
......
......@@ -1045,6 +1045,20 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
}
break;
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
{
mavlink_servo_output_raw_t raw;
mavlink_msg_servo_output_raw_decode(&message, &raw);
if (hilEnabled)
{
emit hilActuatorsChanged(static_cast<uint64_t>(getUnixTimeFromMs(raw.time_boot_ms)), static_cast<float>(raw.servo1_raw),
static_cast<float>(raw.servo2_raw), static_cast<float>(raw.servo3_raw),
static_cast<float>(raw.servo4_raw), static_cast<float>(raw.servo5_raw), static_cast<float>(raw.servo6_raw),
static_cast<float>(raw.servo7_raw), static_cast<float>(raw.servo8_raw));
}
}
break;
#ifdef MAVLINK_ENABLED_PIXHAWK
case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
{
......@@ -1096,6 +1110,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
}
break;
#endif
// case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT:
// {
......@@ -1205,7 +1222,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
case MAVLINK_MSG_ID_RAW_PRESSURE:
case MAVLINK_MSG_ID_SCALED_PRESSURE:
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
case MAVLINK_MSG_ID_OPTICAL_FLOW:
case MAVLINK_MSG_ID_DEBUG_VECT:
case MAVLINK_MSG_ID_DEBUG:
......@@ -2394,8 +2410,8 @@ void UAS::disarmSystem()
void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust)
{
// Scale values
double rollPitchScaling = 0.2f * 1000.0f;
double yawScaling = 0.5f * 1000.0f;
double rollPitchScaling = 1.0f * 1000.0f;
double yawScaling = 1.0f * 1000.0f;
double thrustScaling = 1.0f * 1000.0f;
manualRollAngle = roll * rollPitchScaling;
......
......@@ -665,6 +665,8 @@ signals:
void imageReady(UASInterface* uas);
/** @brief HIL controls have changed */
void hilControlsChanged(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);
/** @brief HIL actuator outputs have changed */
void hilActuatorsChanged(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
protected:
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
......
......@@ -80,7 +80,7 @@ void JoystickWidget::setZ(float z)
void JoystickWidget::setHat(float x, float y)
{
updateStatus(tr("Hat position: x: %1, y: %2").arg(x, y));
updateStatus(tr("Hat position: x: %1, y: %2").arg(x).arg(y));
}
void JoystickWidget::clearKeys()
......
......@@ -11,6 +11,8 @@ QGCHilConfiguration::QGCHilConfiguration(QGCHilLink* link, QWidget *parent) :
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)));
ui->startButton->setText(tr("Connect"));
......@@ -22,9 +24,17 @@ QGCHilConfiguration::QGCHilConfiguration(QGCHilLink* link, QWidget *parent) :
connect(ui->randomPositionButton, SIGNAL(clicked()), link, SLOT(setRandomPosition()));
connect(ui->airframeComboBox, SIGNAL(activated(QString)), link, SLOT(setAirframe(QString)));
}
ui->hostComboBox->clear();
ui->hostComboBox->addItem(link->getRemoteHost());
// connect(ui->)
}
void QGCHilConfiguration::receiveStatusMessage(const QString& message)
{
ui->statusLabel->setText(message);
}
void QGCHilConfiguration::toggleSimulation(bool connect)
{
Q_UNUSED(connect);
......
......@@ -18,8 +18,10 @@ public:
~QGCHilConfiguration();
public slots:
/** Start / stop simulation */
/** @brief Start / stop simulation */
void toggleSimulation(bool connect);
/** @brief Receive status message */
void receiveStatusMessage(const QString& message);
protected:
QGCHilLink* link;
......
......@@ -7,98 +7,31 @@
<x>0</x>
<y>0</y>
<width>305</width>
<height>202</height>
<height>261</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="40,60,50,50">
<item row="5" column="0" colspan="3">
<widget class="QLabel" name="statusLabel">
<property name="text">
<string>Status</string>
</property>
</widget>
</item>
<item row="6" column="0" colspan="2">
<widget class="QPushButton" name="randomAttitudeButton">
<property name="text">
<string>Random ATT</string>
</property>
</widget>
</item>
<item row="4" column="0" colspan="2">
<widget class="QPushButton" name="startButton">
<property name="text">
<string>Start</string>
</property>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="simLabel">
<property name="text">
<string>Simulator</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="hostLabel">
<property name="text">
<string>Host</string>
</property>
</widget>
</item>
<item row="4" column="2" colspan="2">
<widget class="QPushButton" name="setHomeButton">
<property name="text">
<string>Set HOME</string>
</property>
</widget>
</item>
<item row="2" column="1" colspan="3">
<widget class="QComboBox" name="hostComboBox">
<item row="1" column="1" colspan="3">
<widget class="QComboBox" name="airframeComboBox">
<property name="editable">
<bool>true</bool>
</property>
<item>
<property name="text">
<string>127.0.0.1:49000</string>
<string>QRO_X/MK</string>
</property>
</item>
</widget>
</item>
<item row="0" column="1" colspan="3">
<widget class="QComboBox" name="simComboBox">
<item>
<property name="text">
<string>X-Plane</string>
<string>QRO_X/Ardrone</string>
</property>
</item>
</widget>
</item>
<item row="6" column="2" colspan="2">
<widget class="QPushButton" name="randomPositionButton">
<property name="text">
<string>Random POS</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label">
<property name="text">
<string>Airframe</string>
</property>
</widget>
</item>
<item row="1" column="1" colspan="3">
<widget class="QComboBox" name="airframeComboBox">
<property name="editable">
<bool>true</bool>
</property>
<item>
<property name="text">
<string>QRO_X</string>
<string>QRO_X/PWM</string>
</property>
</item>
<item>
......@@ -133,6 +66,96 @@
</item>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="simLabel">
<property name="text">
<string>Simulator</string>
</property>
</widget>
</item>
<item row="4" column="2" colspan="2">
<widget class="QPushButton" name="setHomeButton">
<property name="text">
<string>Set HOME</string>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="statusLabel">
<property name="text">
<string>Status</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label">
<property name="text">
<string>Airframe</string>
</property>
</widget>
</item>
<item row="0" column="1" colspan="3">
<widget class="QComboBox" name="simComboBox">
<item>
<property name="text">
<string>X-Plane</string>
</property>
</item>
</widget>
</item>
<item row="2" column="1" colspan="3">
<widget class="QComboBox" name="hostComboBox">
<property name="editable">
<bool>true</bool>
</property>
<item>
<property name="text">
<string>127.0.0.1:49000</string>
</property>
</item>
</widget>
</item>
<item row="6" column="2" colspan="2">
<widget class="QPushButton" name="randomPositionButton">
<property name="text">
<string>Random POS</string>
</property>
</widget>
</item>
<item row="6" column="0" colspan="2">
<widget class="QPushButton" name="randomAttitudeButton">
<property name="text">
<string>Random ATT</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="hostLabel">
<property name="text">
<string>Host</string>
</property>
</widget>
</item>
<item row="4" column="0" colspan="2">
<widget class="QPushButton" name="startButton">
<property name="text">
<string>Start</string>
</property>
</widget>
</item>
<item row="8" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
<resources/>
......
......@@ -42,11 +42,6 @@ Q3DWidgetFactory::get(const std::string& type, QWidget* parent)
if (type == "PIXHAWK") {
return QPointer<QWidget>(new Pixhawk3DWidget(parent));
}
#ifdef QGC_OSGEARTH_ENABLED
else if (type == "MAP3D") {
return QPointer<QWidget>(new QMap3D());
}
#endif
else {
return QPointer<QWidget>(new Q3DWidget(parent));
}
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL 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.
QGROUNDCONTROL 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 QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifdef QGC_OSGEARTH_ENABLED
/**
* @file
* @brief Definition of the class QMap3D.
*
* @author James Goppert <james.goppert@gmail.com>
*
*/
#include "QMap3D.h"
#include <osgEarthUtil/EarthManipulator>
#include <QFileDialog>
QMap3D::QMap3D(QWidget * parent, const char * name, WindowFlags f) :
QWidget(parent,f)
{
Q_UNUSED(name);
setupUi(this);
#if ((OPENSCENEGRAPH_MAJOR_VERSION == 2) & (OPENSCENEGRAPH_MINOR_VERSION > 8)) | (OPENSCENEGRAPH_MAJOR_VERSION > 2)
graphicsView->setCameraManipulator(new osgEarth::Util::EarthManipulator);
#else
graphicsView->setCameraManipulator(new osgEarthUtil::EarthManipulator);
#endif
graphicsView->setSceneData(new osg::Group);
graphicsView->updateCamera();
show();
}
QMap3D::~QMap3D()
{
}
void QMap3D::on_pushButton_map_clicked()
{
QString mapName = QFileDialog::getOpenFileName(this, tr("Select an OsgEarth map file"),
QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("OsgEarth file (*.earth);;"));
graphicsView->getSceneData()->asGroup()->addChild(osgDB::readNodeFile(mapName.toStdString()));
graphicsView->updateCamera();
}
void QMap3D::on_pushButton_vehicle_clicked()
{
QString vehicleName = QFileDialog::getOpenFileName(this, tr("Select a 3D model for your vehicle"),
QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("OsgEarth file (*.osg, *.ac, *.3ds);;"));
graphicsView->getSceneData()->asGroup()->addChild(osgDB::readNodeFile(vehicleName.toStdString()));
graphicsView->updateCamera();
}
#endif
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