Browse Source

Substantial cleanup in joystick interface, operational now

QGC4.4
Lorenz Meier 13 years ago
parent
commit
3131d7e52e
  1. 2
      qgroundcontrol.pro
  2. 5
      src/comm/QGCFlightGearLink.cc
  3. 1
      src/comm/QGCFlightGearLink.h
  4. 6
      src/comm/QGCHilLink.h
  5. 279
      src/comm/QGCXPlaneLink.cc
  6. 18
      src/comm/QGCXPlaneLink.h
  7. 15
      src/input/JoystickInput.cc
  8. 22
      src/uas/UAS.cc
  9. 2
      src/uas/UAS.h
  10. 2
      src/ui/JoystickWidget.cc
  11. 10
      src/ui/QGCHilConfiguration.cc
  12. 4
      src/ui/QGCHilConfiguration.h
  13. 169
      src/ui/QGCHilConfiguration.ui
  14. 5
      src/ui/map3D/Q3DWidgetFactory.cc
  15. 73
      src/ui/map3D/QMap3D.cc

2
qgroundcontrol.pro

@ -557,7 +557,7 @@ contains(DEPENDENCIES_PRESENT, osg) { @@ -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) {

5
src/comm/QGCFlightGearLink.cc

@ -142,6 +142,11 @@ void QGCFlightGearLink::setRemoteHost(const QString& host) @@ -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

1
src/comm/QGCFlightGearLink.h

@ -78,6 +78,7 @@ public slots: @@ -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();

6
src/comm/QGCHilLink.h

@ -31,6 +31,7 @@ public slots: @@ -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: @@ -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

279
src/comm/QGCXPlaneLink.cc

@ -44,7 +44,9 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress @@ -44,7 +44,9 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress
mav(mav),
socket(NULL),
process(NULL),
terraSync(NULL)
terraSync(NULL),
airframeID(QGCXPlaneLink::AIRFRAME_UNKNOWN),
xPlaneConnected(false)
{
this->localHost = localHost;
this->localPort = localPort/*+mav->getUASID()*/;
@ -68,7 +70,7 @@ void QGCXPlaneLink::loadSettings() @@ -68,7 +70,7 @@ void QGCXPlaneLink::loadSettings()
QSettings settings;
settings.sync();
settings.beginGroup("QGC_XPLANE_LINK");
setRemoteHost(settings.value("REMOTE_HOST", QString("%1:%2").arg(remoteHost.toString(), remotePort)).toString());
setRemoteHost(settings.value("REMOTE_HOST", QString("%1:%2").arg(remoteHost.toString()).arg(remotePort)).toString());
settings.endGroup();
}
@ -173,10 +175,78 @@ void QGCXPlaneLink::setRemoteHost(const QString& newHost) @@ -173,10 +175,78 @@ void QGCXPlaneLink::setRemoteHost(const QString& newHost)
disconnectSimulation();
connectSimulation();
}
emit remoteChanged(QString("%1:%2").arg(remoteHost.toString()).arg(remotePort));
}
void QGCXPlaneLink::updateActuators(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8)
{
// Only update this for multirotors
if (airframeID == AIRFRAME_QUAD_X_MK_10INCH_I2C ||
airframeID == AIRFRAME_QUAD_X_ARDRONE ||
airframeID == AIRFRAME_QUAD_DJI_F450_PWM)
{
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));
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(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode)
{
// Do not update this control type for
// all multirotors
if (airframeID == AIRFRAME_QUAD_X_MK_10INCH_I2C ||
airframeID == AIRFRAME_QUAD_X_ARDRONE ||
airframeID == AIRFRAME_QUAD_DJI_F450_PWM)
{
return;
}
#pragma pack(push, 1)
struct payload {
@ -218,6 +288,7 @@ void QGCXPlaneLink::updateControls(uint64_t time, float rollAilerons, float pitc @@ -218,6 +288,7 @@ void QGCXPlaneLink::updateControls(uint64_t time, float rollAilerons, float pitc
void QGCXPlaneLink::writeBytes(const char* data, qint64 size)
{
if (!data) return;
//#define QGCXPlaneLink_DEBUG
#if 1
QString bytes;
@ -277,11 +348,14 @@ void QGCXPlaneLink::readBytes() @@ -277,11 +348,14 @@ void QGCXPlaneLink::readBytes()
} p;
#pragma pack(pop)
bool oldConnectionState = xPlaneConnected;
if (data[0] == 'D' &&
data[1] == 'A' &&
data[2] == 'T' &&
data[3] == 'A')
{
xPlaneConnected = true;
for (unsigned i = 0; i < nsegs; i++)
{
@ -296,15 +370,17 @@ void QGCXPlaneLink::readBytes() @@ -296,15 +370,17 @@ void QGCXPlaneLink::readBytes()
//qDebug() << "SPEEDS:" << "airspeed" << airspeed << "m/s, groundspeed" << groundspeed << "m/s";
}
else if (p.index == 8)
{
//qDebug() << "MAN:" << p.f[0] << p.f[3] << p.f[7];
man_roll = p.f[0];
man_pitch = p.f[1];
man_yaw = p.f[2];
UAS* uas = dynamic_cast<UAS*>(mav);
if (uas) uas->setManualControlCommands(man_roll, man_pitch, man_yaw, 0.6);
}
// Forward controls from X-Plane to MAV, not very useful
// better: Connect Joystick to QGroundControl
// else if (p.index == 8)
// {
// //qDebug() << "MAN:" << p.f[0] << p.f[3] << p.f[7];
// man_roll = p.f[0];
// man_pitch = p.f[1];
// man_yaw = p.f[2];
// UAS* uas = dynamic_cast<UAS*>(mav);
// if (uas) uas->setManualControlCommands(man_roll, man_pitch, man_yaw, 0.6);
// }
else if (p.index == 16)
{
//qDebug() << "ANG VEL:" << p.f[0] << p.f[3] << p.f[7];
@ -377,6 +453,11 @@ void QGCXPlaneLink::readBytes() @@ -377,6 +453,11 @@ void QGCXPlaneLink::readBytes()
pitchspeed, yawspeed, lat*1E7, lon*1E7, alt*1E3,
vx, vy, vz, xacc*1000, yacc*1000, zacc*1000);
if (!oldConnectionState && xPlaneConnected)
{
emit statusMessage("Receiving from XPlane.");
}
// // Echo data for debugging purposes
// std::cerr << __FILE__ << __LINE__ << "Received datagram:" << std::endl;
// int i;
@ -415,6 +496,7 @@ bool QGCXPlaneLink::disconnectSimulation() @@ -415,6 +496,7 @@ bool QGCXPlaneLink::disconnectSimulation()
if (mav)
{
disconnect(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)));
disconnect(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)));
disconnect(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)));
UAS* uas = dynamic_cast<UAS*>(mav);
if (uas)
@ -449,7 +531,23 @@ bool QGCXPlaneLink::disconnectSimulation() @@ -449,7 +531,23 @@ bool QGCXPlaneLink::disconnectSimulation()
void QGCXPlaneLink::selectPlane(const QString& plane)
{
airframeName = plane;
if (plane.contains("QRO"))
{
if (plane.contains("MK"))
{
airframeID = AIRFRAME_QUAD_X_MK_10INCH_I2C;
}
else if (plane.contains("ARDRONE"))
{
airframeID = AIRFRAME_QUAD_X_ARDRONE;
}
else
{
airframeID = AIRFRAME_QUAD_DJI_F450_PWM;
}
}
}
void QGCXPlaneLink::setPositionAttitude(double lat, double lon, double alt, double roll, double pitch, double yaw)
@ -569,6 +667,7 @@ bool QGCXPlaneLink::connectSimulation() @@ -569,6 +667,7 @@ bool QGCXPlaneLink::connectSimulation()
//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)));
UAS* uas = dynamic_cast<UAS*>(mav);
@ -618,164 +717,6 @@ bool QGCXPlaneLink::connectSimulation() @@ -618,164 +717,6 @@ bool QGCXPlaneLink::connectSimulation()
ip.use_ip = 1;
writeBytes((const char*)&ip, sizeof(ip));
// XXX This will later be enabled to start X-Plane from within QGroundControl with the right arguments
// //connect(&refreshTimer, SIGNAL(timeout()), this, SLOT(sendUAVUpdate()));
// // Catch process error
// QObject::connect( process, SIGNAL(error(QProcess::ProcessError)),
// this, SLOT(processError(QProcess::ProcessError)));
// QObject::connect( terraSync, SIGNAL(error(QProcess::ProcessError)),
// this, SLOT(processError(QProcess::ProcessError)));
// // Start X-Plane
// QStringList processCall;
// QString processFgfs;
// QString processTerraSync;
// QString fgRoot;
// QString fgScenery;
// QString aircraft;
// if (mav->getSystemType() == MAV_TYPE_FIXED_WING)
// {
// aircraft = "Rascal110-JSBSim";
// }
// else if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
// {
// aircraft = "arducopter";
// }
// else
// {
// aircraft = "Rascal110-JSBSim";
// }
//#ifdef Q_OS_MACX
// processFgfs = "/Applications/X-Plane.app/Contents/Resources/fgfs";
// processTerraSync = "/Applications/X-Plane.app/Contents/Resources/terrasync";
// fgRoot = "/Applications/X-Plane.app/Contents/Resources/data";
// //fgScenery = "/Applications/X-Plane.app/Contents/Resources/data/Scenery";
// fgScenery = "/Applications/X-Plane.app/Contents/Resources/data/Scenery-TerraSync";
// // /Applications/X-Plane.app/Contents/Resources/data/Scenery:
//#endif
//#ifdef Q_OS_WIN32
// processFgfs = "C:\\Program Files (x86)\\X-Plane\\bin\\Win32\\fgfs";
// fgRoot = "C:\\Program Files (x86)\\X-Plane\\data";
// fgScenery = "C:\\Program Files (x86)\\X-Plane\\data\\Scenery-Terrasync";
//#endif
//#ifdef Q_OS_LINUX
// processFgfs = "fgfs";
// fgRoot = "/usr/share/X-Plane/data";
// fgScenery = "/usr/share/X-Plane/data/Scenery-Terrasync";
//#endif
// // Sanity checks
// bool sane = true;
// QFileInfo executable(processFgfs);
// if (!executable.isExecutable())
// {
// MainWindow::instance()->showCriticalMessage(tr("X-Plane Failed to Start"), tr("X-Plane was not found at %1").arg(processFgfs));
// sane = false;
// }
// QFileInfo root(fgRoot);
// if (!root.isDir())
// {
// MainWindow::instance()->showCriticalMessage(tr("X-Plane Failed to Start"), tr("X-Plane data directory was not found at %1").arg(fgRoot));
// sane = false;
// }
// QFileInfo scenery(fgScenery);
// if (!scenery.isDir())
// {
// MainWindow::instance()->showCriticalMessage(tr("X-Plane Failed to Start"), tr("X-Plane scenery directory was not found at %1").arg(fgScenery));
// sane = false;
// }
// if (!sane) return false;
// // --atlas=socket,out,1,locallocalHost,5505,udp
// // terrasync -p 5505 -S -d /usr/local/share/TerraSync
// processCall << QString("--fg-root=%1").arg(fgRoot);
// processCall << QString("--fg-scenery=%1").arg(fgScenery);
// if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
// {
// // FIXME ADD QUAD-Specific protocol here
// processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(localPort);
// processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(remotePort);
// }
// else
// {
// processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(localPort);
// processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(remotePort);
// }
// processCall << "--atlas=socket,out,1,locallocalHost,5505,udp";
// processCall << "--in-air";
// processCall << "--roll=0";
// processCall << "--pitch=0";
// processCall << "--vc=90";
// processCall << "--heading=300";
// processCall << "--timeofday=noon";
// processCall << "--disable-hud-3d";
// processCall << "--disable-fullscreen";
// processCall << "--geometry=400x300";
// processCall << "--disable-anti-alias-hud";
// processCall << "--wind=0@0";
// processCall << "--turbulence=0.0";
// processCall << "--prop:/sim/frame-rate-throttle-hz=30";
// processCall << "--control=mouse";
// processCall << "--disable-intro-music";
// processCall << "--disable-sound";
// processCall << "--disable-random-objects";
// processCall << "--disable-ai-models";
// processCall << "--shading-flat";
// processCall << "--fog-disable";
// processCall << "--disable-specular-highlight";
// //processCall << "--disable-skyblend";
// processCall << "--disable-random-objects";
// processCall << "--disable-panel";
// //processCall << "--disable-horizon-effect";
// processCall << "--disable-clouds";
// processCall << "--fdm=jsb";
// processCall << "--units-meters";
// if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
// {
// // Start all engines of the quad
// processCall << "--prop:/engines/engine[0]/running=true";
// processCall << "--prop:/engines/engine[1]/running=true";
// processCall << "--prop:/engines/engine[2]/running=true";
// processCall << "--prop:/engines/engine[3]/running=true";
// }
// else
// {
// processCall << "--prop:/engines/engine/running=true";
// }
// processCall << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude());
// processCall << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude());
// processCall << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude());
// // Add new argument with this: processCall << "";
// processCall << QString("--aircraft=%2").arg(aircraft);
// QStringList terraSyncArguments;
// terraSyncArguments << "-p 5505";
// terraSyncArguments << "-S";
// terraSyncArguments << QString("-d=%1").arg(fgScenery);
// terraSync->start(processTerraSync, terraSyncArguments);
// process->start(processFgfs, processCall);
// emit X-PlaneConnected(connectState);
// if (connectState) {
// emit X-PlaneConnected();
// connectionStartTime = QGC::groundTimeUsecs()/1000;
// }
// qDebug() << "STARTING SIM";
// qDebug() << "STARTING: " << processFgfs << processCall;
return connectState;
}

18
src/comm/QGCXPlaneLink.h

@ -81,6 +81,16 @@ public: @@ -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: @@ -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: @@ -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);

15
src/input/JoystickInput.cc

@ -214,19 +214,20 @@ void JoystickInput::run() @@ -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

22
src/uas/UAS.cc

@ -1045,6 +1045,20 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -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) @@ -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) @@ -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() @@ -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;

2
src/uas/UAS.h

@ -665,6 +665,8 @@ signals: @@ -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 */

2
src/ui/JoystickWidget.cc

@ -80,7 +80,7 @@ void JoystickWidget::setZ(float z) @@ -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()

10
src/ui/QGCHilConfiguration.cc

@ -11,6 +11,8 @@ QGCHilConfiguration::QGCHilConfiguration(QGCHilLink* link, QWidget *parent) : @@ -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) : @@ -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);

4
src/ui/QGCHilConfiguration.h

@ -18,8 +18,10 @@ public: @@ -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;

169
src/ui/QGCHilConfiguration.ui

@ -7,98 +7,31 @@ @@ -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 @@ @@ -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/>

5
src/ui/map3D/Q3DWidgetFactory.cc

@ -42,11 +42,6 @@ Q3DWidgetFactory::get(const std::string& type, QWidget* parent) @@ -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));
}

73
src/ui/map3D/QMap3D.cc

@ -1,73 +0,0 @@ @@ -1,73 +0,0 @@
/*=====================================================================
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
Loading…
Cancel
Save