Commit d67300d0 authored by Lorenz Meier's avatar Lorenz Meier

WIP on mp_merge integration

parents 7c57e2e5 5131983d
[Heading%20PID%20Tuning]
QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Heading D Gain
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_D
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=200
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=1
QGC_TOOL_WIDGET_ITEMS\2\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_DESCRIPTION=Heading P Gain
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_P
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_COMPONENTID=200
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MAX=5
QGC_TOOL_WIDGET_ITEMS\3\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_DESCRIPTION=Heading I Gain
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_I
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_COMPONENTID=200
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MAX=1
QGC_TOOL_WIDGET_ITEMS\4\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_DESCRIPTION=Heading I Limit
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_IMAX
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_COMPONENTID=200
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MAX=3000
QGC_TOOL_WIDGET_ITEMS\size=4
...@@ -226,7 +226,8 @@ FORMS += src/ui/MainWindow.ui \ ...@@ -226,7 +226,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCHilJSBSimConfiguration.ui \ src/ui/QGCHilJSBSimConfiguration.ui \
src/ui/QGCHilXPlaneConfiguration.ui \ src/ui/QGCHilXPlaneConfiguration.ui \
src/ui/designer/QGCComboBox.ui \ src/ui/designer/QGCComboBox.ui \
src/ui/designer/QGCTextLabel.ui src/ui/designer/QGCTextLabel.ui \
src/ui/uas/UASQuickView.ui
INCLUDEPATH += src \ INCLUDEPATH += src \
src/ui \ src/ui \
src/ui/linechart \ src/ui/linechart \
...@@ -372,7 +373,10 @@ HEADERS += src/MG.h \ ...@@ -372,7 +373,10 @@ HEADERS += src/MG.h \
src/ui/QGCHilXPlaneConfiguration.h \ src/ui/QGCHilXPlaneConfiguration.h \
src/ui/designer/QGCComboBox.h \ src/ui/designer/QGCComboBox.h \
src/ui/designer/QGCTextLabel.h \ src/ui/designer/QGCTextLabel.h \
src/ui/submainwindow.h src/ui/submainwindow.h \
src/ui/dockwidgettitlebareventfilter.h \
src/ui/uas/UASQuickView.h \
src/ui/uas/UASQuickViewItem.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
...@@ -537,7 +541,10 @@ SOURCES += src/main.cc \ ...@@ -537,7 +541,10 @@ SOURCES += src/main.cc \
src/ui/QGCHilXPlaneConfiguration.cc \ src/ui/QGCHilXPlaneConfiguration.cc \
src/ui/designer/QGCComboBox.cc \ src/ui/designer/QGCComboBox.cc \
src/ui/designer/QGCTextLabel.cc \ src/ui/designer/QGCTextLabel.cc \
src/ui/submainwindow.cpp src/ui/submainwindow.cpp \
src/ui/dockwidgettitlebareventfilter.cpp \
src/ui/uas/UASQuickViewItem.cc \
src/ui/uas/UASQuickView.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......
...@@ -11,14 +11,14 @@ ...@@ -11,14 +11,14 @@
#define WITH_TEXT_TO_SPEECH 1 #define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl" #define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 1.0.7 (beta)" #define QGC_APPLICATION_VERSION "v. 1.0.8 (beta)"
namespace QGC namespace QGC
{ {
const QString APPNAME = "QGROUNDCONTROL"; const QString APPNAME = "QGROUNDCONTROL";
const QString COMPANYNAME = "QGROUNDCONTROL"; const QString COMPANYNAME = "QGROUNDCONTROL";
const int APPLICATIONVERSION = 107; // 1.0.7 const int APPLICATIONVERSION = 108; // 1.0.8
} }
#endif // QGC_CONFIGURATION_H #endif // QGC_CONFIGURATION_H
...@@ -64,7 +64,6 @@ void msgHandler( QtMsgType type, const char* msg ) ...@@ -64,7 +64,6 @@ void msgHandler( QtMsgType type, const char* msg )
int main(int argc, char *argv[]) int main(int argc, char *argv[])
{ {
// install the message handler // install the message handler
#ifdef Q_OS_WIN #ifdef Q_OS_WIN
qInstallMsgHandler( msgHandler ); qInstallMsgHandler( msgHandler );
......
...@@ -77,16 +77,10 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), ...@@ -77,16 +77,10 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
localX(0.0), localX(0.0),
localY(0.0), localY(0.0),
localZ(0.0), localZ(0.0),
latitude(0.0),
longitude(0.0),
altitude(0.0),
globalEstimatorActive(false), globalEstimatorActive(false),
latitude_gps(0.0), latitude_gps(0.0),
longitude_gps(0.0), longitude_gps(0.0),
altitude_gps(0.0), altitude_gps(0.0),
roll(0.0),
pitch(0.0),
yaw(0.0),
statusTimeout(new QTimer(this)), statusTimeout(new QTimer(this)),
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES) #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
receivedOverlayTimestamp(0.0), receivedOverlayTimestamp(0.0),
...@@ -624,9 +618,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -624,9 +618,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (!wrongComponent) if (!wrongComponent)
{ {
lastAttitude = time; lastAttitude = time;
roll = QGC::limitAngleToPMPIf(attitude.roll); //roll = QGC::limitAngleToPMPIf(attitude.roll);
pitch = QGC::limitAngleToPMPIf(attitude.pitch); setRoll(QGC::limitAngleToPMPIf(attitude.roll));
yaw = QGC::limitAngleToPMPIf(attitude.yaw); //pitch = QGC::limitAngleToPMPIf(attitude.pitch);
setPitch(QGC::limitAngleToPMPIf(attitude.pitch));
//yaw = QGC::limitAngleToPMPIf(attitude.yaw);
setYaw(QGC::limitAngleToPMPIf(attitude.yaw));
// // Emit in angles // // Emit in angles
...@@ -646,7 +643,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -646,7 +643,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// } // }
attitudeKnown = true; attitudeKnown = true;
emit attitudeChanged(this, roll, pitch, yaw, time); emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time); emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
} }
} }
...@@ -680,8 +677,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -680,8 +677,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (!attitudeKnown) if (!attitudeKnown)
{ {
yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI); //yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
emit attitudeChanged(this, roll, pitch, yaw, time); setYaw(QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI));
emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
} }
emit altitudeChanged(uasId, hud.alt); emit altitudeChanged(uasId, hud.alt);
...@@ -737,14 +735,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -737,14 +735,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_global_position_int_t pos; mavlink_global_position_int_t pos;
mavlink_msg_global_position_int_decode(&message, &pos); mavlink_msg_global_position_int_decode(&message, &pos);
quint64 time = getUnixTime(); quint64 time = getUnixTime();
latitude = pos.lat/(double)1E7; //latitude = pos.lat/(double)1E7;
longitude = pos.lon/(double)1E7; setLatitude(pos.lat/(double)1E7);
altitude = pos.alt/1000.0; //longitude = pos.lon/(double)1E7;
setLongitude(pos.lon/(double)1E7);
//altitude = pos.alt/1000.0;
setAltitude(pos.alt/1000.0);
globalEstimatorActive = true; globalEstimatorActive = true;
speedX = pos.vx/100.0; speedX = pos.vx/100.0;
speedY = pos.vy/100.0; speedY = pos.vy/100.0;
speedZ = pos.vz/100.0; speedZ = pos.vz/100.0;
emit globalPositionChanged(this, latitude, longitude, altitude, time); emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitude(), time);
emit speedChanged(this, speedX, speedY, speedZ, time); emit speedChanged(this, speedX, speedY, speedZ, time);
// Set internal state // Set internal state
...@@ -777,18 +778,23 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -777,18 +778,23 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
loc_type = 0; loc_type = 0;
} }
emit localizationChanged(this, loc_type); emit localizationChanged(this, loc_type);
setSatelliteCount(pos.satellites_visible);
if (pos.fix_type > 2) if (pos.fix_type > 2)
{ {
latitude_gps = pos.lat/(double)1E7; latitude_gps = pos.lat/(double)1E7;
longitude_gps = pos.lon/(double)1E7; longitude_gps = pos.lon/(double)1E7;
altitude_gps = pos.alt/1000.0; altitude_gps = pos.alt/1000.0;
if (!globalEstimatorActive) { if (!globalEstimatorActive) {
latitude = latitude_gps; //latitude = latitude_gps;
longitude = longitude_gps; setLatitude(latitude_gps);
altitude = altitude_gps; //longitude = longitude_gps;
emit globalPositionChanged(this, latitude, longitude, altitude, time); setLongitude(longitude_gps);
//altitude = altitude_gps;
setAltitude(altitude_gps);
emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitude(), time);
} }
positionLock = true; positionLock = true;
...@@ -819,6 +825,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -819,6 +825,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{ {
emit gpsSatelliteStatusChanged(uasId, (unsigned char)pos.satellite_prn[i], (unsigned char)pos.satellite_elevation[i], (unsigned char)pos.satellite_azimuth[i], (unsigned char)pos.satellite_snr[i], static_cast<bool>(pos.satellite_used[i])); emit gpsSatelliteStatusChanged(uasId, (unsigned char)pos.satellite_prn[i], (unsigned char)pos.satellite_elevation[i], (unsigned char)pos.satellite_azimuth[i], (unsigned char)pos.satellite_snr[i], static_cast<bool>(pos.satellite_used[i]));
} }
setSatelliteCount(pos.satellites_visible);
} }
break; break;
case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN: case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
...@@ -1337,6 +1344,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -1337,6 +1344,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
case MAVLINK_MSG_ID_RAW_IMU: case MAVLINK_MSG_ID_RAW_IMU:
case MAVLINK_MSG_ID_SCALED_IMU: case MAVLINK_MSG_ID_SCALED_IMU:
case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT: case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
{
//mavlink_set_local_position_setpoint_t p;
//mavlink_msg_set_local_position_setpoint_decode(&message, &p);
//emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw);
mavlink_nav_controller_output_t p;
mavlink_msg_nav_controller_output_decode(&message,&p);
setDistToWaypoint(p.wp_dist);
}
break;
case MAVLINK_MSG_ID_RAW_PRESSURE: case MAVLINK_MSG_ID_RAW_PRESSURE:
case MAVLINK_MSG_ID_SCALED_PRESSURE: case MAVLINK_MSG_ID_SCALED_PRESSURE:
case MAVLINK_MSG_ID_OPTICAL_FLOW: case MAVLINK_MSG_ID_OPTICAL_FLOW:
......
...@@ -100,30 +100,99 @@ public: ...@@ -100,30 +100,99 @@ public:
/** @brief Get the links associated with this robot */ /** @brief Get the links associated with this robot */
QList<LinkInterface*>* getLinks(); QList<LinkInterface*>* getLinks();
Q_PROPERTY(double localX READ getLocalX WRITE setLocalX NOTIFY localXChanged)
Q_PROPERTY(double localY READ getLocalY WRITE setLocalY NOTIFY localYChanged)
Q_PROPERTY(double localZ READ getLocalZ WRITE setLocalZ NOTIFY localZChanged)
Q_PROPERTY(double latitude READ getLatitude WRITE setLatitude NOTIFY latitudeChanged)
Q_PROPERTY(double longitude READ getLongitude WRITE setLongitude NOTIFY longitudeChanged)
Q_PROPERTY(double altitude READ getAltitude WRITE setAltitude NOTIFY altitudeChanged)
Q_PROPERTY(double satelliteCount READ getSatelliteCount WRITE setSatelliteCount NOTIFY satelliteCountChanged)
Q_PROPERTY(bool isLocalPositionKnown READ localPositionKnown)
Q_PROPERTY(bool isGlobalPositionKnown READ globalPositionKnown)
Q_PROPERTY(double roll READ getRoll WRITE setRoll NOTIFY rollChanged)
Q_PROPERTY(double pitch READ getPitch WRITE setPitch NOTIFY pitchChanged)
Q_PROPERTY(double yaw READ getYaw WRITE setYaw NOTIFY yawChanged)
Q_PROPERTY(double distToWaypoint READ getDistToWaypoint WRITE setDistToWaypoint NOTIFY distToWaypointChanged)
void setLocalX(double val)
{
localX = val;
emit localXChanged(val,"localX");
emit valueChanged(this->uasId,"localX","M",QVariant(val),getUnixTime());
}
double getLocalX() const double getLocalX() const
{ {
return localX; return localX;
} }
void setLocalY(double val)
{
localY = val;
emit localYChanged(val,"localY");
emit valueChanged(this->uasId,"localY","M",QVariant(val),getUnixTime());
}
double getLocalY() const double getLocalY() const
{ {
return localY; return localY;
} }
void setLocalZ(double val)
{
localZ = val;
emit localZChanged(val,"localZ");
emit valueChanged(this->uasId,"localZ","M",QVariant(val),getUnixTime());
}
double getLocalZ() const double getLocalZ() const
{ {
return localZ; return localZ;
} }
void setLatitude(double val)
{
latitude = val;
emit latitudeChanged(val,"latitude");
emit valueChanged(this->uasId,"latitude","deg",QVariant(val),getUnixTime());
}
double getLatitude() const double getLatitude() const
{ {
return latitude; return latitude;
} }
void setLongitude(double val)
{
longitude = val;
emit longitudeChanged(val,"longitude");
emit valueChanged(this->uasId,"longitude","deg",QVariant(val),getUnixTime());
}
double getLongitude() const double getLongitude() const
{ {
return longitude; return longitude;
} }
void setAltitude(double val)
{
altitude = val;
emit altitudeChanged(val,"altitude");
emit valueChanged(this->uasId,"altitude","M",QVariant(val),getUnixTime());
}
double getAltitude() const double getAltitude() const
{ {
return altitude; return altitude;
} }
void setSatelliteCount(double val)
{
satelliteCount = val;
emit satelliteCountChanged(val,"satelliteCount");
emit valueChanged(this->uasId,"satelliteCount","M",QVariant(val),getUnixTime());
}
double getSatelliteCount() const
{
return satelliteCount;
}
virtual bool localPositionKnown() const virtual bool localPositionKnown() const
{ {
return isLocalPositionKnown; return isLocalPositionKnown;
...@@ -133,14 +202,46 @@ public: ...@@ -133,14 +202,46 @@ public:
return isGlobalPositionKnown; return isGlobalPositionKnown;
} }
void setDistToWaypoint(double val)
{
distToWaypoint = val;
emit distToWaypointChanged(val,"distToWaypoint");
emit valueChanged(this->uasId,"distToWaypoint","M",QVariant(val),getUnixTime());
}
double getDistToWaypoint() const
{
return distToWaypoint;
}
void setRoll(double val)
{
roll = val;
emit rollChanged(val,"roll");
}
double getRoll() const double getRoll() const
{ {
return roll; return roll;
} }
void setPitch(double val)
{
pitch = val;
emit pitchChanged(val,"pitch");
}
double getPitch() const double getPitch() const
{ {
return pitch; return pitch;
} }
void setYaw(double val)
{
yaw = val;
emit yawChanged(val,"yaw");
}
double getYaw() const double getYaw() const
{ {
return yaw; return yaw;
...@@ -281,6 +382,7 @@ protected: //COMMENTS FOR TEST UNIT ...@@ -281,6 +382,7 @@ protected: //COMMENTS FOR TEST UNIT
double latitude; ///< Global latitude as estimated by position estimator double latitude; ///< Global latitude as estimated by position estimator
double longitude; ///< Global longitude as estimated by position estimator double longitude; ///< Global longitude as estimated by position estimator
double altitude; ///< Global altitude as estimated by position estimator double altitude; ///< Global altitude as estimated by position estimator
double satelliteCount; ///< Number of satellites visible to raw GPS
bool globalEstimatorActive; ///< Global position estimator present, do not fall back to GPS raw for position bool globalEstimatorActive; ///< Global position estimator present, do not fall back to GPS raw for position
double latitude_gps; ///< Global latitude as estimated by raw GPS double latitude_gps; ///< Global latitude as estimated by raw GPS
double longitude_gps; ///< Global longitude as estimated by raw GPS double longitude_gps; ///< Global longitude as estimated by raw GPS
...@@ -288,6 +390,7 @@ protected: //COMMENTS FOR TEST UNIT ...@@ -288,6 +390,7 @@ protected: //COMMENTS FOR TEST UNIT
double speedX; ///< True speed in X axis double speedX; ///< True speed in X axis
double speedY; ///< True speed in Y axis double speedY; ///< True speed in Y axis
double speedZ; ///< True speed in Z axis double speedZ; ///< True speed in Z axis
double distToWaypoint; ///< Distance to next waypoint
double roll; double roll;
double pitch; double pitch;
double yaw; double yaw;
...@@ -699,6 +802,21 @@ signals: ...@@ -699,6 +802,21 @@ signals:
/** @brief HIL actuator outputs have changed */ /** @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); void hilActuatorsChanged(uint64_t 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);
void localZChanged(double val,QString name);
void longitudeChanged(double val,QString name);
void latitudeChanged(double val,QString name);
void altitudeChanged(double val,QString name);
void altitudeChanged(int uasid, double altitude);
void rollChanged(double val,QString name);
void pitchChanged(double val,QString name);
void yawChanged(double val,QString name);
void satelliteCountChanged(double val,QString name);
void distToWaypointChanged(double val,QString name);
protected: protected:
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */ /** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
quint64 getUnixTime(quint64 time=0); quint64 getUnixTime(quint64 time=0);
......
...@@ -449,6 +449,7 @@ signals: ...@@ -449,6 +449,7 @@ signals:
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec); void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec); void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec); void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs);
void voltageChanged(int uasId, double voltage); void voltageChanged(int uasId, double voltage);
void waypointUpdated(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool active); void waypointUpdated(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool active);
......
...@@ -235,7 +235,8 @@ UASManager::UASManager() : ...@@ -235,7 +235,8 @@ UASManager::UASManager() :
homeLat(47.3769), homeLat(47.3769),
homeLon(8.549444), homeLon(8.549444),
homeAlt(470.0), homeAlt(470.0),
homeFrame(MAV_FRAME_GLOBAL) homeFrame(MAV_FRAME_GLOBAL),
offlineUASWaypointManager(NULL)
{ {
loadSettings(); loadSettings();
setLocalNEDSafetyBorders(1, -1, 0, -1, 1, -1); setLocalNEDSafetyBorders(1, -1, 0, -1, 1, -1);
...@@ -280,6 +281,22 @@ void UASManager::addUAS(UASInterface* uas) ...@@ -280,6 +281,22 @@ void UASManager::addUAS(UASInterface* uas)
if (firstUAS) if (firstUAS)
{ {
setActiveUAS(uas); setActiveUAS(uas);
if (offlineUASWaypointManager->getWaypointEditableList().size() > 0)
{
if (QMessageBox::question(0,"Question","Do you want to append the offline waypoints to the ones currently on the UAV?",QMessageBox::Yes,QMessageBox::No) == QMessageBox::Yes)
{
//Need to transfer all waypoints from the offline mode WPManager to the online mode.
for (int i=0;i<offlineUASWaypointManager->getWaypointEditableList().size();i++)
{
Waypoint *wp = uas->getWaypointManager()->createWaypoint();
wp->setLatitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getLatitude());
wp->setLongitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getLongitude());
wp->setAltitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getAltitude());
}
}
offlineUASWaypointManager->deleteLater();
offlineUASWaypointManager = 0;
}
} }
} }
...@@ -336,6 +353,20 @@ UASInterface* UASManager::silentGetActiveUAS() ...@@ -336,6 +353,20 @@ UASInterface* UASManager::silentGetActiveUAS()
{ {
return activeUAS; ///< Return zero pointer if no UAS has been loaded return activeUAS; ///< Return zero pointer if no UAS has been loaded
} }
UASWaypointManager *UASManager::getActiveUASWaypointManager()
{
if (activeUAS)
{
return activeUAS->getWaypointManager();
}
if (!offlineUASWaypointManager)
{
offlineUASWaypointManager = new UASWaypointManager(NULL);
}
return offlineUASWaypointManager;
}
bool UASManager::launchActiveUAS() bool UASManager::launchActiveUAS()
{ {
......
...@@ -58,6 +58,12 @@ public: ...@@ -58,6 +58,12 @@ public:
* @return NULL pointer if no UAS exists, active UAS else * @return NULL pointer if no UAS exists, active UAS else
**/ **/
UASInterface* getActiveUAS(); UASInterface* getActiveUAS();
/**
* @brief getActiveUASWaypointManager
* @return uas->getUASWaypointManager(), or if not connected, a singleton instance of a UASWaypointManager.
*/
UASWaypointManager *getActiveUASWaypointManager();
UASInterface* silentGetActiveUAS(); UASInterface* silentGetActiveUAS();
/** /**
* @brief Get the UAS with this id * @brief Get the UAS with this id
...@@ -244,6 +250,7 @@ protected: ...@@ -244,6 +250,7 @@ protected:
UASManager(); UASManager();
QList<UASInterface*> systems; QList<UASInterface*> systems;
UASInterface* activeUAS; UASInterface* activeUAS;
UASWaypointManager *offlineUASWaypointManager;
QMutex activeUASMutex; QMutex activeUASMutex;
double homeLat; double homeLat;
double homeLon; double homeLon;
......
This diff is collapsed.
...@@ -119,6 +119,12 @@ public: ...@@ -119,6 +119,12 @@ public:
return autoReconnect; return autoReconnect;
} }
/** @brief Get title bar mode setting */
bool dockWidgetTitleBarsEnabled()
{
return dockWidgetTitleBarEnabled;
}
/** @brief Get low power mode setting */ /** @brief Get low power mode setting */
bool lowPowerModeEnabled() bool lowPowerModeEnabled()
{ {
...@@ -186,6 +192,8 @@ public slots: ...@@ -186,6 +192,8 @@ public slots:
void reloadStylesheet(); void reloadStylesheet();
/** @brief Let the user select the CSS style sheet */ /** @brief Let the user select the CSS style sheet */
void selectStylesheet(); void selectStylesheet();
/** @breif Enable title bars on dock widgets when no in advanced mode */
void enableDockWidgetTitleBars(bool enabled);
/** @brief Automatically reconnect last link */ /** @brief Automatically reconnect last link */
void enableAutoReconnect(bool enabled); void enableAutoReconnect(bool enabled);
/** @brief Save power by reducing update rates */ /** @brief Save power by reducing update rates */
...@@ -343,7 +351,7 @@ void createDockWidget(QWidget *parent,QWidget *child,QString title,QString objec ...@@ -343,7 +351,7 @@ void createDockWidget(QWidget *parent,QWidget *child,QString title,QString objec
QPointer<SubMainWindow> simView; QPointer<SubMainWindow> simView;
// Center widgets // Center widgets
//QPointer<Linecharts> linechartWidget; QPointer<Linecharts> linechartWidget;
//QPointer<HUD> hudWidget; //QPointer<HUD> hudWidget;
//QPointer<QGCVehicleConfig> configWidget; //QPointer<QGCVehicleConfig> configWidget;
//QPointer<QGCMapTool> mapWidget; //QPointer<QGCMapTool> mapWidget;
...@@ -436,6 +444,7 @@ private: ...@@ -436,6 +444,7 @@ private:
QMap<QDockWidget*,QWidget*> dockToTitleBarMap; QMap<QDockWidget*,QWidget*> dockToTitleBarMap;
QMap<VIEW_SECTIONS,QMap<QString,QWidget*> > centralWidgetToDockWidgetsMap; QMap<VIEW_SECTIONS,QMap<QString,QWidget*> > centralWidgetToDockWidgetsMap;
bool isAdvancedMode; bool isAdvancedMode;
bool dockWidgetTitleBarEnabled;
Ui::MainWindow ui; Ui::MainWindow ui;
QString getWindowStateKey(); QString getWindowStateKey();
......
...@@ -42,6 +42,10 @@ QGCSettingsWidget::QGCSettingsWidget(QWidget *parent, Qt::WindowFlags flags) : ...@@ -42,6 +42,10 @@ QGCSettingsWidget::QGCSettingsWidget(QWidget *parent, Qt::WindowFlags flags) :
ui->lowPowerCheckBox->setChecked(MainWindow::instance()->lowPowerModeEnabled()); ui->lowPowerCheckBox->setChecked(MainWindow::instance()->lowPowerModeEnabled());
connect(ui->lowPowerCheckBox, SIGNAL(clicked(bool)), MainWindow::instance(), SLOT(enableLowPowerMode(bool))); connect(ui->lowPowerCheckBox, SIGNAL(clicked(bool)), MainWindow::instance(), SLOT(enableLowPowerMode(bool)));
//Dock widget title bars
ui->titleBarCheckBox->setChecked(MainWindow::instance()->dockWidgetTitleBarsEnabled());
connect(ui->titleBarCheckBox,SIGNAL(clicked(bool)),MainWindow::instance(),SLOT(enableDockWidgetTitleBars(bool)));
// Style // Style
MainWindow::QGC_MAINWINDOW_STYLE style = (MainWindow::QGC_MAINWINDOW_STYLE)MainWindow::instance()->getStyle(); MainWindow::QGC_MAINWINDOW_STYLE style = (MainWindow::QGC_MAINWINDOW_STYLE)MainWindow::instance()->getStyle();
switch (style) { switch (style) {
......
...@@ -46,7 +46,7 @@ ...@@ -46,7 +46,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="0"> <item row="4" column="0">
<widget class="QRadioButton" name="nativeStyle"> <widget class="QRadioButton" name="nativeStyle">
<property name="text"> <property name="text">
<string>Use native platform look and feel (Windows/Linux/Mac OS)</string> <string>Use native platform look and feel (Windows/Linux/Mac OS)</string>
...@@ -56,14 +56,14 @@ ...@@ -56,14 +56,14 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="4" column="0"> <item row="5" column="0">
<widget class="QRadioButton" name="indoorStyle"> <widget class="QRadioButton" name="indoorStyle">
<property name="text"> <property name="text">
<string>Use indoor mission style (black background)</string> <string>Use indoor mission style (black background)</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="0"> <item row="6" column="0">
<widget class="QRadioButton" name="outdoorStyle"> <widget class="QRadioButton" name="outdoorStyle">
<property name="text"> <property name="text">
<string>Use outdoor mission style (light background)</string> <string>Use outdoor mission style (light background)</string>
...@@ -80,6 +80,16 @@ ...@@ -80,6 +80,16 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="0">
<widget class="QCheckBox" name="titleBarCheckBox">
<property name="text">
<string>Show Docked Widget title bars when NOT in advanced Mode.</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout> </layout>
</widget> </widget>
</widget> </widget>
......
...@@ -154,7 +154,7 @@ void QGCComboBox::selectParameter(int paramIndex) ...@@ -154,7 +154,7 @@ void QGCComboBox::selectParameter(int paramIndex)
if (uas->getParamManager()) if (uas->getParamManager())
{ {
// Current value // Current value
uas->getParamManager()->requestParameterUpdate(component, parameterName); //uas->getParamManager()->requestParameterUpdate(component, parameterName);
// Minimum // Minimum
if (uas->getParamManager()->isParamMinKnown(parameterName)) if (uas->getParamManager()->isParamMinKnown(parameterName))
......
...@@ -184,7 +184,7 @@ void QGCParamSlider::selectParameter(int paramIndex) ...@@ -184,7 +184,7 @@ void QGCParamSlider::selectParameter(int paramIndex)
if (uas->getParamManager()) if (uas->getParamManager())
{ {
// Current value // Current value
uas->getParamManager()->requestParameterUpdate(component, parameterName); //uas->getParamManager()->requestParameterUpdate(component, parameterName);
// Minimum // Minimum
if (uas->getParamManager()->isParamMinKnown(parameterName)) if (uas->getParamManager()->isParamMinKnown(parameterName))
......
...@@ -117,11 +117,13 @@ QList<QGCToolWidget*> QGCToolWidget::createWidgetsFromSettings(QWidget* parent, ...@@ -117,11 +117,13 @@ QList<QGCToolWidget*> QGCToolWidget::createWidgetsFromSettings(QWidget* parent,
{ {
settings->setArrayIndex(i); settings->setArrayIndex(i);
QString name = settings->value("TITLE", "").toString(); QString name = settings->value("TITLE", "").toString();
QString objname = settings->value("OBJECT_NAME", "").toString();
if (!instances()->contains(name) && name.length() != 0) if (!instances()->contains(name) && name.length() != 0)
{ {
//qDebug() << "CREATED WIDGET:" << name; //qDebug() << "CREATED WIDGET:" << name;
QGCToolWidget* tool = new QGCToolWidget(name, parent, settings); QGCToolWidget* tool = new QGCToolWidget(name, parent, settings);
tool->setObjectName(objname);
newWidgets.append(tool); newWidgets.append(tool);
} }
else if (name.length() == 0) else if (name.length() == 0)
...@@ -403,6 +405,7 @@ void QGCToolWidget::storeWidgetsToSettings(QString settingsFile) ...@@ -403,6 +405,7 @@ void QGCToolWidget::storeWidgetsToSettings(QString settingsFile)
{ {
settings->setArrayIndex(num++); settings->setArrayIndex(num++);
settings->setValue("TITLE", instances()->values().at(i)->getTitle()); settings->setValue("TITLE", instances()->values().at(i)->getTitle());
settings->setValue("OBJECT_NAME", instances()->values().at(i)->objectName());
//qDebug() << "WRITING TITLE" << instances()->values().at(i)->getTitle(); //qDebug() << "WRITING TITLE" << instances()->values().at(i)->getTitle();
} }
} }
......
#include "dockwidgettitlebareventfilter.h"
#include <QDebug>
#include <QEvent>
DockWidgetTitleBarEventFilter::DockWidgetTitleBarEventFilter(QObject *parent) : QObject(parent)
{
}
bool DockWidgetTitleBarEventFilter::eventFilter(QObject *object,QEvent *event)
{
qDebug() << event->type();
if (event->type() == QEvent::MouseButtonPress || event->type() == QEvent::MouseButtonRelease)
{
return true;
}
return QObject::eventFilter(object,event);
}
#ifndef DOCKWIDGETTITLEBAREVENTFILTER_H
#define DOCKWIDGETTITLEBAREVENTFILTER_H
#include <QObject>
class DockWidgetTitleBarEventFilter : public QObject
{
Q_OBJECT
public:
explicit DockWidgetTitleBarEventFilter(QObject *parent = 0);
protected:
bool eventFilter(QObject *object,QEvent *event);
signals:
public slots:
};
#endif // DOCKWIDGETTITLEBAREVENTFILTER_H
...@@ -9,7 +9,6 @@ ...@@ -9,7 +9,6 @@
QGCMapWidget::QGCMapWidget(QWidget *parent) : QGCMapWidget::QGCMapWidget(QWidget *parent) :
mapcontrol::OPMapWidget(parent), mapcontrol::OPMapWidget(parent),
currWPManager(NULL),
firingWaypointChange(NULL), firingWaypointChange(NULL),
maxUpdateInterval(2.1f), // 2 seconds maxUpdateInterval(2.1f), // 2 seconds
followUAVEnabled(false), followUAVEnabled(false),
...@@ -17,17 +16,42 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) : ...@@ -17,17 +16,42 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) :
trailInterval(2.0f), trailInterval(2.0f),
followUAVID(0), followUAVID(0),
mapInitialized(false), mapInitialized(false),
homeAltitude(0) homeAltitude(0),
uas(0)
{ {
//currWPManager = new UASWaypointManager(NULL); //Create a waypoint manager that is null.
currWPManager = UASManager::instance()->getActiveUASWaypointManager();
connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)));
connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)));
offlineMode = true;
// Widget is inactive until shown // Widget is inactive until shown
defaultGuidedAlt = -1; defaultGuidedAlt = -1;
loadSettings(false); loadSettings(false);
this->setContextMenuPolicy(Qt::ActionsContextMenu); this->setContextMenuPolicy(Qt::ActionsContextMenu);
QAction *guidedaction = new QAction(this);
guidedaction->setText("Go To Here (Guided Mode)");
connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedActionTriggered()));
this->addAction(guidedaction);
guidedaction = new QAction(this);
guidedaction->setText("Go To Here Alt (Guided Mode)");
connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedAltActionTriggered()));
this->addAction(guidedaction);
QAction *cameraaction = new QAction(this);
cameraaction->setText("Point Camera Here");
connect(cameraaction,SIGNAL(triggered()),this,SLOT(cameraActionTriggered()));
this->addAction(cameraaction);
} }
void QGCMapWidget::guidedActionTriggered() void QGCMapWidget::guidedActionTriggered()
{ {
if (!uas)
{
QMessageBox::information(0,"Error","Please connect first");
return;
}
if (currWPManager) if (currWPManager)
{ {
if (defaultGuidedAlt == -1) if (defaultGuidedAlt == -1)
...@@ -49,6 +73,11 @@ void QGCMapWidget::guidedActionTriggered() ...@@ -49,6 +73,11 @@ void QGCMapWidget::guidedActionTriggered()
} }
bool QGCMapWidget::guidedAltActionTriggered() bool QGCMapWidget::guidedAltActionTriggered()
{ {
if (!uas)
{
QMessageBox::information(0,"Error","Please connect first");
return false;
}
bool ok = false; bool ok = false;
int tmpalt = QInputDialog::getInt(this,"Altitude","Enter default altitude (in meters) of destination point for guided mode",100,0,30000,1,&ok); int tmpalt = QInputDialog::getInt(this,"Altitude","Enter default altitude (in meters) of destination point for guided mode",100,0,30000,1,&ok);
if (!ok) if (!ok)
...@@ -62,6 +91,11 @@ bool QGCMapWidget::guidedAltActionTriggered() ...@@ -62,6 +91,11 @@ bool QGCMapWidget::guidedAltActionTriggered()
} }
void QGCMapWidget::cameraActionTriggered() void QGCMapWidget::cameraActionTriggered()
{ {
if (!uas)
{
QMessageBox::information(0,"Error","Please connect first");
return;
}
ArduPilotMegaMAV *newmav = qobject_cast<ArduPilotMegaMAV*>(this->uas); ArduPilotMegaMAV *newmav = qobject_cast<ArduPilotMegaMAV*>(this->uas);
if (newmav) if (newmav)
{ {
...@@ -262,32 +296,14 @@ void QGCMapWidget::activeUASSet(UASInterface* uas) ...@@ -262,32 +296,14 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
if (uas) if (uas)
{ {
//UASWaypointManager *old = currWPManager;
currWPManager = uas->getWaypointManager(); currWPManager = uas->getWaypointManager();
QList<QAction*> actionList = this->actions();
for (int i=0;i<actionList.size();i++) updateSelectedSystem(uas->getUASID());
{ followUAVID = uas->getUASID();
this->removeAction(actionList[i]);
actionList[i]->deleteLater(); updateWaypointList(uas->getUASID());
}
if (currWPManager->guidedModeSupported())
{
QAction *guidedaction = new QAction(this);
guidedaction->setText("Go To Here (Guided Mode)");
connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedActionTriggered()));
this->addAction(guidedaction);
guidedaction = new QAction(this);
guidedaction->setText("Go To Here Alt (Guided Mode)");
connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedAltActionTriggered()));
this->addAction(guidedaction);
if (uas->getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
QAction *cameraaction = new QAction(this);
cameraaction->setText("Point Camera Here");
connect(cameraaction,SIGNAL(triggered()),this,SLOT(cameraActionTriggered()));
this->addAction(cameraaction);
}
}
// Connect the waypoint manager / data storage to the UI // Connect the waypoint manager / data storage to the UI
connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int))); connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
...@@ -295,11 +311,27 @@ void QGCMapWidget::activeUASSet(UASInterface* uas) ...@@ -295,11 +311,27 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*))); connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)));
connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*))); connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)));
updateSelectedSystem(uas->getUASID()); /*if (offlineMode)
followUAVID = uas->getUASID(); {
if (QMessageBox::question(0,"Question","Do you want to append the offline waypoints to the ones currently on the UAV?",QMessageBox::Yes,QMessageBox::No) == QMessageBox::Yes)
{
//Need to transfer all waypoints from the offline mode WPManager to the online mode.
for (int i=0;i<old->getWaypointEditableList().size();i++)
{
Waypoint *wp = currWPManager->createWaypoint();
wp->setLatitude(old->getWaypointEditableList()[i]->getLatitude());
wp->setLongitude(old->getWaypointEditableList()[i]->getLongitude());
wp->setAltitude(old->getWaypointEditableList()[i]->getAltitude());
}
}
offlineMode = false;
old->deleteLater();
}*/
// Delete all waypoints and add waypoint from new system // Delete all waypoints and add waypoint from new system
updateWaypointList(uas->getUASID());
} }
} }
...@@ -563,7 +595,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) ...@@ -563,7 +595,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
// Currently only accept waypoint updates from the UAS in focus // Currently only accept waypoint updates from the UAS in focus
// this has to be changed to accept read-only updates from other systems as well. // this has to be changed to accept read-only updates from other systems as well.
UASInterface* uasInstance = UASManager::instance()->getUASForId(uas); UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
if (uasInstance->getWaypointManager() == currWPManager || uas == -1) if (!uasInstance || uasInstance->getWaypointManager() == currWPManager || uas == -1)
{ {
// Only accept waypoints in global coordinate frame // Only accept waypoints in global coordinate frame
if (((wp->getFrame() == MAV_FRAME_GLOBAL) || (wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType()) if (((wp->getFrame() == MAV_FRAME_GLOBAL) || (wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType())
......
...@@ -137,6 +137,7 @@ protected: ...@@ -137,6 +137,7 @@ protected:
void mouseDoubleClickEvent(QMouseEvent* event); void mouseDoubleClickEvent(QMouseEvent* event);
UASWaypointManager* currWPManager; ///< The current waypoint manager UASWaypointManager* currWPManager; ///< The current waypoint manager
bool offlineMode;
QMap<Waypoint* , mapcontrol::WayPointItem*> waypointsToIcons; QMap<Waypoint* , mapcontrol::WayPointItem*> waypointsToIcons;
QMap<mapcontrol::WayPointItem*, Waypoint*> iconsToWaypoints; QMap<mapcontrol::WayPointItem*, Waypoint*> iconsToWaypoints;
Waypoint* firingWaypointChange; Waypoint* firingWaypointChange;
......
#include "UASQuickView.h"
#include <QMetaMethod>
#include <QDebug>
UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(setActiveUAS(UASInterface*)));
connect(UASManager::instance(),SIGNAL(UASCreated(UASInterface*)),this,SLOT(addUAS(UASInterface*)));
if (UASManager::instance()->getActiveUAS())
{
addUAS(UASManager::instance()->getActiveUAS());
}
this->setContextMenuPolicy(Qt::ActionsContextMenu);
{
QAction *action = new QAction("latitude",this);
action->setCheckable(true);
action->setChecked(true);
connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
this->addAction(action);
UASQuickViewItem *item = new UASQuickViewItem(this);
item->setTitle("latitude");
ui.verticalLayout->addWidget(item);
uasPropertyToLabelMap["latitude"] = item;
}
{
QAction *action = new QAction("longitude",this);
action->setCheckable(true);
action->setChecked(true);
connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
this->addAction(action);
UASQuickViewItem *item = new UASQuickViewItem(this);
item->setTitle("longitude");
ui.verticalLayout->addWidget(item);
uasPropertyToLabelMap["longitude"] = item;
}
{
QAction *action = new QAction("altitude",this);
action->setCheckable(true);
action->setChecked(true);
connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
this->addAction(action);
UASQuickViewItem *item = new UASQuickViewItem(this);
item->setTitle("altitude");
ui.verticalLayout->addWidget(item);
uasPropertyToLabelMap["altitude"] = item;
}
{
QAction *action = new QAction("satelliteCount",this);
action->setCheckable(true);
action->setChecked(true);
connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
this->addAction(action);
UASQuickViewItem *item = new UASQuickViewItem(this);
item->setTitle("satelliteCount");
ui.verticalLayout->addWidget(item);
uasPropertyToLabelMap["satelliteCount"] = item;
}
{
QAction *action = new QAction("distToWaypoint",this);
action->setCheckable(true);
action->setChecked(true);
connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
this->addAction(action);
UASQuickViewItem *item = new UASQuickViewItem(this);
item->setTitle("distToWaypoint");
ui.verticalLayout->addWidget(item);
uasPropertyToLabelMap["distToWaypoint"] = item;
}
updateTimer = new QTimer(this);
connect(updateTimer,SIGNAL(timeout()),this,SLOT(updateTimerTick()));
updateTimer->start(1000);
}
void UASQuickView::updateTimerTick()
{
for (int i=0;i<uasPropertyList.size();i++)
{
if (uasPropertyValueMap.contains(uasPropertyList[i]) && uasPropertyToLabelMap.contains(uasPropertyList[i]))
{
uasPropertyToLabelMap[uasPropertyList[i]]->setValue(uasPropertyValueMap.value(uasPropertyList[i],0));
}
}
}
void UASQuickView::addUAS(UASInterface* uas)
{
if (uas)
{
if (!this->uas)
{
setActiveUAS(uas);
}
}
}
void UASQuickView::setActiveUAS(UASInterface* uas)
{
if (!uas)
{
return;
}
this->uas = uas;
connect(uas,SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)),this,SLOT(valueChanged(int,QString,QString,QVariant,quint64)));
uasPropertyList.clear();
qDebug() << "UASInfoWidget property count:" << uas->metaObject()->propertyCount();
for (int i=0;i<uas->metaObject()->propertyCount();i++)
{
if (uas->metaObject()->property(i).hasNotifySignal())
{
qDebug() << "Property:" << i << uas->metaObject()->property(i).name();
uasPropertyList.append(uas->metaObject()->property(i).name());
if (!uasPropertyToLabelMap.contains(uas->metaObject()->property(i).name()))
{
QAction *action = new QAction(QString(uas->metaObject()->property(i).name()),this);
action->setCheckable(true);
connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
this->addAction(action);
}
qDebug() << "Signature:" << uas->metaObject()->property(i).notifySignal().signature();
int val = this->metaObject()->indexOfMethod("valChanged(double,QString)");
if (val != -1)
{
if (!connect(uas,uas->metaObject()->property(i).notifySignal(),this,this->metaObject()->method(val)))
{
qDebug() << "Error connecting signal";
}
}
}
}
}
void UASQuickView::actionTriggered(bool checked)
{
QAction *senderlabel = qobject_cast<QAction*>(sender());
if (!senderlabel)
{
return;
}
if (checked)
{
UASQuickViewItem *item = new UASQuickViewItem(this);
item->setTitle(senderlabel->text());
ui.verticalLayout->addWidget(item);
uasPropertyToLabelMap[senderlabel->text()] = item;
}
else
{
ui.verticalLayout->removeWidget(uasPropertyToLabelMap[senderlabel->text()]);
uasPropertyToLabelMap[senderlabel->text()]->deleteLater();
uasPropertyToLabelMap.remove(senderlabel->text());
}
}
void UASQuickView::valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs)
{
uasPropertyValueMap[name] = value.toDouble();
}
void UASQuickView::valChanged(double val,QString type)
{
//qDebug() << "Value changed:" << type << val;
// uasPropertyValueMap[type] = val;
}
#ifndef UASQUICKVIEW_H
#define UASQUICKVIEW_H
#include <QWidget>
#include <QTimer>
#include <QLabel>
#include "uas/UASManager.h"
#include "uas/UASInterface.h"
#include "ui_UASQuickView.h"
#include "UASQuickViewItem.h"
class UASQuickView : public QWidget
{
Q_OBJECT
public:
UASQuickView(QWidget *parent = 0);
private:
UASInterface *uas;
QList<QString> uasPropertyList;
QMap<QString,double> uasPropertyValueMap;
QMap<QString,UASQuickViewItem*> uasPropertyToLabelMap;
QTimer *updateTimer;
protected:
Ui::Form ui;
signals:
public slots:
void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs);
void actionTriggered(bool checked);
void updateTimerTick();
void addUAS(UASInterface* uas);
void setActiveUAS(UASInterface* uas);
void valChanged(double val,QString type);
};
#endif // UASQUICKVIEW_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>Form</class>
<widget class="QWidget" name="Form">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
</rect>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>100</height>
</size>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QVBoxLayout" name="verticalLayout"/>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#include "UASQuickViewItem.h"
#include <QVBoxLayout>
UASQuickViewItem::UASQuickViewItem(QWidget *parent) : QWidget(parent)
{
QVBoxLayout *layout = new QVBoxLayout();
this->setLayout(layout);
titleLabel = new QLabel(this);
titleLabel->setAlignment(Qt::AlignHCenter);
this->layout()->addWidget(titleLabel);
valueLabel = new QLabel(this);
valueLabel->setAlignment(Qt::AlignHCenter);
valueLabel->setText("<h1>0.00</h1>");
this->layout()->addWidget(valueLabel);
layout->addSpacerItem(new QSpacerItem(20, 40, QSizePolicy::Minimum, QSizePolicy::Expanding));
}
void UASQuickViewItem::setValue(double value)
{
valueLabel->setText("<h1>" + QString::number(value,'f',4) + "</h1>");
}
void UASQuickViewItem::setTitle(QString title)
{
titleLabel->setText(title);
}
#ifndef UASQUICKVIEWITEM_H
#define UASQUICKVIEWITEM_H
#include <QWidget>
#include <QLabel>
class UASQuickViewItem : public QWidget
{
Q_OBJECT
public:
explicit UASQuickViewItem(QWidget *parent = 0);
void setValue(double value);
void setTitle(QString title);
private:
QLabel *titleLabel;
QLabel *valueLabel;
signals:
public slots:
};
#endif // UASQUICKVIEWITEM_H
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