From 81ccc01dd3c95f54eed380db5f42d43fbbaa9499 Mon Sep 17 00:00:00 2001 From: pixhawk Date: Fri, 4 Feb 2011 17:12:58 +0100 Subject: [PATCH] Minor improvements throughout the application to improve usability --- src/comm/MAVLinkSimulationMAV.cc | 19 +-- src/uas/PxQuadMAV.cc | 22 +--- src/uas/UAS.cc | 32 +++-- src/ui/HSIDisplay.cc | 220 ++++++++++++++++++------------- src/ui/HSIDisplay.h | 2 + src/ui/MainWindow.cc | 16 ++- src/ui/MapWidget.cc | 6 + 7 files changed, 180 insertions(+), 137 deletions(-) diff --git a/src/comm/MAVLinkSimulationMAV.cc b/src/comm/MAVLinkSimulationMAV.cc index 2c2fc3511..1d8fc3bf5 100644 --- a/src/comm/MAVLinkSimulationMAV.cc +++ b/src/comm/MAVLinkSimulationMAV.cc @@ -121,8 +121,8 @@ void MAVLinkSimulationMAV::mainloop() pos.alt = z*1000.0; pos.lat = y*1E7; pos.lon = x*1E7; - pos.vx = 0; - pos.vy = 0; + pos.vx = sin(yaw)*10.0f; + pos.vy = cos(yaw)*10.0f; pos.vz = 0; mavlink_msg_global_position_int_encode(systemid, MAV_COMP_ID_IMU, &msg, &pos); link->sendMAVLinkMessage(&msg); @@ -164,18 +164,21 @@ void MAVLinkSimulationMAV::mainloop() control_status.control_pos_xy = 1; control_status.control_pos_yaw = 1; control_status.control_pos_z = 1; + control_status.gps_fix = 2; // 2D GPS fix + control_status.position_fix = 3; // 3D fix from GPS + barometric pressure + control_status.vision_fix = 0; // no fix from vision system mavlink_msg_control_status_encode(systemid, MAV_COMP_ID_IMU, &ret, &control_status); link->sendMAVLinkMessage(&ret); // Send actual controller outputs // This message just shows the direction // and magnitude of the control output - mavlink_position_controller_output_t pos; - pos.x = sin(yaw)*127.0f; - pos.y = cos(yaw)*127.0f; - pos.z = 0; - mavlink_msg_position_controller_output_encode(systemid, MAV_COMP_ID_IMU, &ret, &pos); - link->sendMAVLinkMessage(&ret); +// mavlink_position_controller_output_t pos; +// pos.x = sin(yaw)*127.0f; +// pos.y = cos(yaw)*127.0f; +// pos.z = 0; +// mavlink_msg_position_controller_output_encode(systemid, MAV_COMP_ID_IMU, &ret, &pos); +// link->sendMAVLinkMessage(&ret); // Send a named value with name "FLOAT" and 0.5f as value diff --git a/src/uas/PxQuadMAV.cc b/src/uas/PxQuadMAV.cc index 841d5655a..cb78497f3 100644 --- a/src/uas/PxQuadMAV.cc +++ b/src/uas/PxQuadMAV.cc @@ -50,9 +50,9 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) if (message.sysid == uasId) { - QString uasState; - QString stateDescription; - QString patternPath; +// QString uasState; +// QString stateDescription; +// QString patternPath; switch (message.msgid) { case MAVLINK_MSG_ID_RAW_AUX: @@ -155,22 +155,6 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) emit valueChanged(uasId, "Load", "%", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow()); } break; - case MAVLINK_MSG_ID_CONTROL_STATUS: - { - mavlink_control_status_t status; - mavlink_msg_control_status_decode(&message, &status); - // Emit control status vector - emit attitudeControlEnabled(static_cast(status.control_att)); - emit positionXYControlEnabled(static_cast(status.control_pos_xy)); - emit positionZControlEnabled(static_cast(status.control_pos_z)); - emit positionYawControlEnabled(static_cast(status.control_pos_yaw)); - - // Emit localization status vector - emit localizationChanged(this, status.position_fix); - emit visionLocalizationChanged(this, status.vision_fix); - emit gpsLocalizationChanged(this, status.gps_fix); - } - break; default: // Do nothing break; diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 8ce3ce5b4..061cdd5aa 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -349,6 +349,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) } } break; + case MAVLINK_MSG_ID_CONTROL_STATUS: + { + mavlink_control_status_t status; + mavlink_msg_control_status_decode(&message, &status); + // Emit control status vector + emit attitudeControlEnabled(static_cast(status.control_att)); + emit positionXYControlEnabled(static_cast(status.control_pos_xy)); + emit positionZControlEnabled(static_cast(status.control_pos_z)); + emit positionYawControlEnabled(static_cast(status.control_pos_yaw)); + + // Emit localization status vector + emit localizationChanged(this, status.position_fix); + emit visionLocalizationChanged(this, status.vision_fix); + emit gpsLocalizationChanged(this, status.gps_fix); + } + break; case MAVLINK_MSG_ID_RAW_IMU: { mavlink_raw_imu_t raw; @@ -480,6 +496,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit valueChanged(uasId, "gps z speed", "m/s", speedZ, time); emit globalPositionChanged(this, longitude, latitude, altitude, time); emit speedChanged(this, speedX, speedY, speedZ, time); + emit valueChanged(uasId, "gpsspeed", "m/s", sqrt(speedX*speedX+speedY*speedY+speedZ*speedZ), time); // Set internal state if (!positionLock) { @@ -506,15 +523,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit valueChanged(uasId, "latitude", "deg", pos.lat, time); emit valueChanged(uasId, "longitude", "deg", pos.lon, time); - // FIXME REMOVE - longitude = pos.lon; - latitude = pos.lat; - altitude = pos.alt; - emit globalPositionChanged(this, longitude, latitude, altitude, time); - if (pos.fix_type > 0) { emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time); + emit valueChanged(uasId, "gpsspeed", "m/s", pos.v, time); // Check for NaN int alt = pos.alt; @@ -560,9 +572,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_raw_pressure_t pressure; mavlink_msg_raw_pressure_decode(&message, &pressure); quint64 time = this->getUnixTime(0); - emit valueChanged(uasId, "abs pressure", "hP", pressure.press_abs, time); - emit valueChanged(uasId, "diff pressure 1", "hP", pressure.press_diff1, time); - emit valueChanged(uasId, "diff pressure 2", "hP", pressure.press_diff2, time); + emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time); + emit valueChanged(uasId, "diff pressure 1", "hPa", pressure.press_diff1, time); + emit valueChanged(uasId, "diff pressure 2", "hPa", pressure.press_diff2, time); } break; case MAVLINK_MSG_ID_RC_CHANNELS_RAW: @@ -1017,7 +1029,7 @@ void UAS::forwardMessage(mavlink_message_t message) { if(serial != links->at(i)) { - qDebug()<<"Forwarding Over link: "<getName()<<" "<getName()<<" "<setInterval(updateInterval); @@ -117,13 +118,14 @@ HSIDisplay::HSIDisplay(QWidget *parent) : QDoubleSpinBox* spinBox = new QDoubleSpinBox(this); spinBox->setMinimum(0.1); spinBox->setMaximum(9999); + spinBox->setMaximumWidth(50); spinBox->setValue(metricWidth); spinBox->setToolTip(tr("Ground width in meters shown on instrument")); spinBox->setStatusTip(tr("Ground width in meters shown on instrument")); connect(spinBox, SIGNAL(valueChanged(double)), this, SLOT(setMetricWidth(double))); connect(this, SIGNAL(metricWidthChanged(double)), spinBox, SLOT(setValue(double))); layout->addWidget(spinBox); - layout->setAlignment(spinBox, Qt::AlignBottom | Qt::AlignLeft); + layout->setAlignment(spinBox, Qt::AlignBottom | Qt::AlignRight); this->setLayout(layout); uas = NULL; @@ -159,6 +161,10 @@ void HSIDisplay::resetMAVState() setPointKnown = false; localAvailable = 0; globalAvailable = 0; + + // Setpoints + positionSetPointKnown = false; + setPointKnown = false; } void HSIDisplay::paintEvent(QPaintEvent * event) @@ -224,9 +230,9 @@ void HSIDisplay::renderOverlay() // Draw center indicator QPolygonF p(3); - p.replace(0, QPointF(xCenterPos, yCenterPos-2.8484f)); - p.replace(1, QPointF(xCenterPos-2.0f, yCenterPos+2.0f)); - p.replace(2, QPointF(xCenterPos+2.0f, yCenterPos+2.0f)); + p.replace(0, QPointF(xCenterPos, yCenterPos-4.0f)); + p.replace(1, QPointF(xCenterPos-4.0f, yCenterPos+3.5f)); + p.replace(2, QPointF(xCenterPos+4.0f, yCenterPos+3.5f)); drawPolygon(p, &painter); // ---------------------- @@ -247,13 +253,13 @@ void HSIDisplay::renderOverlay() // Draw position setpoints in body coordinates - if (uiXSetCoordinate != 0 || uiYSetCoordinate != 0) + if (userSetPointSet) { QColor spColor(150, 150, 150); drawSetpointXY(uiXSetCoordinate, uiYSetCoordinate, uiYawSet, spColor, painter); } - if (bodyXSetCoordinate != 0 || bodyYSetCoordinate != 0) + if (positionSetPointKnown) { // Draw setpoint drawSetpointXY(bodyXSetCoordinate, bodyYSetCoordinate, bodyYawSet, QGC::colorCyan, painter); @@ -268,30 +274,6 @@ void HSIDisplay::renderOverlay() // Labels on outer part and bottom - if (localAvailable > 0) - { - // Position - QString str; - str.sprintf("%05.2f %05.2f %05.2f m", x, y, z); - paintText(str, ringColor, 3.0f, xCenterPos + baseRadius - 30.75f, vheight - 5.0f, &painter); - - // Speed - str.sprintf("%05.2f m/s", speed); - paintText(str, ringColor, 3.0f, 10.0f, vheight - 5.0f, &painter); - } - - if (globalAvailable > 0) - { - // Position - QString str; - str.sprintf("%05.2f lat %06.2f lon %06.2f alt", lat, lon, alt); - paintText(str, ringColor, 2.2f, xCenterPos + baseRadius - 30.75f, vheight - 5.0f, &painter); - - // Speed - str.sprintf("%05.2f m/s", speed); - paintText(str, ringColor, 2.2f, 10.0f, vheight - 5.0f, &painter); - } - // Draw waypoints drawWaypoints(painter); @@ -306,11 +288,42 @@ void HSIDisplay::renderOverlay() drawPositionLock(22, 5, tr("VIS"), visionFix, visionFixKnown, painter); drawPositionLock(44, 5, tr("GPS"), gpsFix, gpsFixKnown, painter); drawPositionLock(66, 5, tr("IRU"), iruFix, iruFixKnown, painter); + + // Draw speed to top left + paintText(tr("SPEED"), QGC::colorCyan, 2.2f, 2, 11, &painter); + paintText(tr("%1 m/s").arg(speed, 2, 'f', 2, '0'), Qt::white, 2.2f, 14, 11, &painter); + + // Draw crosstrack error to top right + float crossTrackError = 0; + paintText(tr("XTRACK"), QGC::colorCyan, 2.2f, 62, 11, &painter); + paintText(tr("%1 m").arg(crossTrackError, 2, 'f', 2, '0'), Qt::white, 2.2f, 75, 11, &painter); + + // Draw position to bottom left + if (localAvailable > 0 && globalAvailable == 0) + { + // Position + QString str; + str.sprintf("%05.2f %05.2f %05.2f m", x, y, z); + paintText(tr("POS"), QGC::colorCyan, 2.6f, 2, vheight- 5.0f, &painter); + paintText(str, Qt::white, 2.6f, 10, vheight - 5.0f, &painter); + } + + if (globalAvailable > 0) + { + // Position + QString str; + str.sprintf("%05.2f lat %06.2f lon %06.2f alt", lat, lon, alt); + paintText(tr("GPS"), QGC::colorCyan, 2.6f, 2, vheight- 5.0f, &painter); + paintText(str, Qt::white, 2.6f, 10, vheight - 5.0f, &painter); + } + + // Draw Field of view to bottom right + paintText(tr("FOV"), QGC::colorCyan, 2.6f, 62, vheight- 5.0f, &painter); } void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, bool known, QPainter& painter) { - paintText(label, QGC::colorCyan, 2.6f, x, y+0.35f, &painter); + paintText(label, QGC::colorCyan, 2.6f, x, y+0.8f, &painter); QColor statusColor(250, 250, 250); if(status) { @@ -326,7 +339,7 @@ void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, bo float indicatorHeight = refToScreenY(4.0f); painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), indicatorWidth, indicatorHeight)); - paintText((status) ? tr("ON") : tr("OFF"), statusColor, 2.6f, x+7.9f, y+0.35f, &painter); + paintText((status) ? tr("ON") : tr("OFF"), statusColor, 2.6f, x+7.9f, y+0.8f, &painter); // Cross out instrument if state unknown if (!known) { @@ -351,14 +364,19 @@ void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, bo void HSIDisplay::drawPositionLock(float x, float y, QString label, int status, bool known, QPainter& painter) { - paintText(label, QGC::colorCyan, 2.6f, x, y+0.35f, &painter); + paintText(label, QGC::colorCyan, 2.6f, x, y+0.8f, &painter); QColor negStatusColor(200, 20, 20); + QColor intermediateStatusColor (Qt::yellow); QColor posStatusColor(20, 200, 20); QColor statusColor(250, 250, 250); - if(status > 0 && status < 4) + if (status == 3) { painter.setBrush(posStatusColor); } + else if (status == 2) + { + painter.setBrush(intermediateStatusColor.dark(150)); + } else { painter.setBrush(negStatusColor); @@ -387,7 +405,7 @@ void HSIDisplay::drawPositionLock(float x, float y, QString label, int status, b painter.setPen(Qt::NoPen); painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), refToScreenX(7.0f), refToScreenY(4.0f))); - paintText(lockText, statusColor, 2.6f, x+7.9f, y+0.35f, &painter); + paintText(lockText, statusColor, 2.6f, x+7.9f, y+0.8f, &painter); // Cross out instrument if state unknown if (!known) { @@ -640,6 +658,7 @@ void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesir bodyYawSet = yawDesired; mavInitialized = true; setPointKnown = true; + positionSetPointKnown = true; // qDebug() << "Received setpoint at x: " << x << "metric y:" << y; // posXSet = xDesired; @@ -693,6 +712,7 @@ void HSIDisplay::updateLocalization(UASInterface* uas, int fix) Q_UNUSED(uas); positionFix = fix; positionFixKnown = true; + //qDebug() << "LOCALIZATION FIX CALLED"; } /** * @param fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D localization, 3: 3D localization @@ -711,6 +731,7 @@ void HSIDisplay::updateVisionLocalization(UASInterface* uas, int fix) Q_UNUSED(uas); visionFix = fix; visionFixKnown = true; + //qDebug() << "VISION FIX GOT CALLED"; } /** @@ -945,89 +966,98 @@ void HSIDisplay::drawObjects(QPainter &painter) void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter) { - // Draw the needle - const float maxWidth = radius / 10.0f; - const float minWidth = maxWidth * 0.3f; + if (xyControlKnown && xyControlEnabled) + { + // Draw the needle + const float maxWidth = radius / 10.0f; + const float minWidth = maxWidth * 0.3f; - float angle = atan2(posXSet, -posYSet); - angle -= M_PI/2.0f; + float angle = atan2(posXSet, -posYSet); + angle -= M_PI/2.0f; - QPolygonF p(6); + QPolygonF p(6); - //radius *= ((posXSaturation + posYSaturation) - sqrt(pow(posXSet, 2), pow(posYSet, 2))) / (2*posXSaturation); + //radius *= ((posXSaturation + posYSaturation) - sqrt(pow(posXSet, 2), pow(posYSet, 2))) / (2*posXSaturation); - radius *= sqrt(pow(posXSet, 2) + pow(posYSet, 2)) / sqrt(posXSaturation + posYSaturation); + radius *= sqrt(pow(posXSet, 2) + pow(posYSet, 2)) / sqrt(posXSaturation + posYSaturation); - p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f)); - p.replace(1, QPointF(xRef-minWidth/2.0f, yRef-radius * 0.9f)); - p.replace(2, QPointF(xRef+minWidth/2.0f, yRef-radius * 0.9f)); - p.replace(3, QPointF(xRef+maxWidth/2.0f, yRef-radius * 0.4f)); - p.replace(4, QPointF(xRef, yRef-radius * 0.36f)); - p.replace(5, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f)); + p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f)); + p.replace(1, QPointF(xRef-minWidth/2.0f, yRef-radius * 0.9f)); + p.replace(2, QPointF(xRef+minWidth/2.0f, yRef-radius * 0.9f)); + p.replace(3, QPointF(xRef+maxWidth/2.0f, yRef-radius * 0.4f)); + p.replace(4, QPointF(xRef, yRef-radius * 0.36f)); + p.replace(5, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f)); - rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef)); + rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef)); - QBrush indexBrush; - indexBrush.setColor(color); - indexBrush.setStyle(Qt::SolidPattern); - painter->setPen(Qt::SolidLine); - painter->setPen(color); - painter->setBrush(indexBrush); - drawPolygon(p, painter); + QBrush indexBrush; + indexBrush.setColor(color); + indexBrush.setStyle(Qt::SolidPattern); + painter->setPen(Qt::SolidLine); + painter->setPen(color); + painter->setBrush(indexBrush); + drawPolygon(p, painter); - qDebug() << "DRAWING POS SETPOINT X:" << posXSet << "Y:" << posYSet << angle; + //qDebug() << "DRAWING POS SETPOINT X:" << posXSet << "Y:" << posYSet << angle; + } } void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, const QColor& color, QPainter* painter) { - // Draw the needle - const float maxWidth = radius / 10.0f; - const float minWidth = maxWidth * 0.3f; + if (attControlKnown && attControlEnabled) + { + // Draw the needle + const float maxWidth = radius / 10.0f; + const float minWidth = maxWidth * 0.3f; - float angle = atan2(attXSet, attYSet); - angle -= M_PI/2.0f; + float angle = atan2(attXSet, attYSet); + angle -= M_PI/2.0f; - radius *= sqrt(pow(attXSet, 2) + pow(attYSet, 2)) / sqrt(attXSaturation + attYSaturation); + radius *= sqrt(pow(attXSet, 2) + pow(attYSet, 2)) / sqrt(attXSaturation + attYSaturation); - QPolygonF p(6); + QPolygonF p(6); - p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f)); - p.replace(1, QPointF(xRef-minWidth/2.0f, yRef-radius * 0.9f)); - p.replace(2, QPointF(xRef+minWidth/2.0f, yRef-radius * 0.9f)); - p.replace(3, QPointF(xRef+maxWidth/2.0f, yRef-radius * 0.4f)); - p.replace(4, QPointF(xRef, yRef-radius * 0.36f)); - p.replace(5, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f)); + p.replace(0, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f)); + p.replace(1, QPointF(xRef-minWidth/2.0f, yRef-radius * 0.9f)); + p.replace(2, QPointF(xRef+minWidth/2.0f, yRef-radius * 0.9f)); + p.replace(3, QPointF(xRef+maxWidth/2.0f, yRef-radius * 0.4f)); + p.replace(4, QPointF(xRef, yRef-radius * 0.36f)); + p.replace(5, QPointF(xRef-maxWidth/2.0f, yRef-radius * 0.4f)); - rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef)); + rotatePolygonClockWiseRad(p, angle, QPointF(xRef, yRef)); - QBrush indexBrush; - indexBrush.setColor(color); - indexBrush.setStyle(Qt::SolidPattern); - painter->setPen(Qt::SolidLine); - painter->setPen(color); - painter->setBrush(indexBrush); - drawPolygon(p, painter); + QBrush indexBrush; + indexBrush.setColor(color); + indexBrush.setStyle(Qt::SolidPattern); + painter->setPen(Qt::SolidLine); + painter->setPen(color); + painter->setBrush(indexBrush); + drawPolygon(p, painter); - // TODO Draw Yaw indicator + // TODO Draw Yaw indicator - //qDebug() << "DRAWING ATT SETPOINT X:" << attXSet << "Y:" << attYSet << angle; + //qDebug() << "DRAWING ATT SETPOINT X:" << attXSet << "Y:" << attYSet << angle; + } } void HSIDisplay::drawAltitudeSetpoint(float xRef, float yRef, float radius, const QColor& color, QPainter* painter) { - // Draw the circle - QPen circlePen(Qt::SolidLine); - circlePen.setWidth(refLineWidthToPen(0.5f)); - circlePen.setColor(color); - painter->setBrush(Qt::NoBrush); - painter->setPen(circlePen); - drawCircle(xRef, yRef, radius, 200.0f, color, painter); - //drawCircle(xRef, yRef, radius, 200.0f, 170.0f, 1.0f, color, painter); - - // // Draw the value - // QString label; - // label.sprintf("%05.1f", value); - // paintText(label, color, 4.5f, xRef-7.5f, yRef-2.0f, painter); + if (zControlKnown && zControlEnabled) + { + // Draw the circle + QPen circlePen(Qt::SolidLine); + circlePen.setWidth(refLineWidthToPen(0.5f)); + circlePen.setColor(color); + painter->setBrush(Qt::NoBrush); + painter->setPen(circlePen); + drawCircle(xRef, yRef, radius, 200.0f, color, painter); + //drawCircle(xRef, yRef, radius, 200.0f, 170.0f, 1.0f, color, painter); + + // // Draw the value + // QString label; + // label.sprintf("%05.1f", value); + // paintText(label, color, 4.5f, xRef-7.5f, yRef-2.0f, painter); + } } void HSIDisplay::wheelEvent(QWheelEvent* event) diff --git a/src/ui/HSIDisplay.h b/src/ui/HSIDisplay.h index a6b12f7c1..7282e1da1 100644 --- a/src/ui/HSIDisplay.h +++ b/src/ui/HSIDisplay.h @@ -248,6 +248,8 @@ protected: // Data indicators bool setPointKnown; ///< Controller setpoint known status flag + bool positionSetPointKnown; ///< Position setpoint known status flag + bool userSetPointSet; private: }; diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 472856125..cce5d8e4e 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -210,6 +210,8 @@ void MainWindow::setDefaultSettingsForAp() settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_UAS_LIST,VIEW_OPERATOR), true); // ENABLE HUD TOOL WIDGET settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_HUD,VIEW_OPERATOR), true); + // ENABLE WAYPOINTS + settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_WAYPOINTS,VIEW_OPERATOR), true); } // ENGINEER VIEW DEFAULT @@ -399,15 +401,19 @@ void MainWindow::buildPxWidgets() acceptList->append("-105,pitch,deg,+105,s"); acceptList->append("-105,yaw,deg,+105,s"); - acceptList->append("-260,rollspeed,deg/s,+260,s"); - acceptList->append("-260,pitchspeed,deg/s,+260,s"); - acceptList->append("-260,yawspeed,deg/s,+260,s"); + acceptList->append("-60,rollspeed,deg/s,+60,s"); + acceptList->append("-60,pitchspeed,deg/s,+60,s"); + acceptList->append("-60,yawspeed,deg/s,+60,s"); + acceptList->append("0,airspeed,m/s,30"); + acceptList->append("0,gpsspeed,m/s,30"); + acceptList->append("0,truespeed,m/s,30"); //FIXME: memory of acceptList2 will never be freed again QStringList* acceptList2 = new QStringList(); acceptList2->append("0,abs pressure,hPa,65500"); - acceptList2->append("-999,accel. X,raw,999,s"); - acceptList2->append("-999,accel. Y,raw,999,s"); + acceptList2->append("-2048,accel. x,raw,2048,s"); + acceptList2->append("-2048,accel. y,raw,2048,s"); + acceptList2->append("-2048,accel. z,raw,2048,s"); if (!linechartWidget) { diff --git a/src/ui/MapWidget.cc b/src/ui/MapWidget.cc index de8752537..0c70fbd75 100644 --- a/src/ui/MapWidget.cc +++ b/src/ui/MapWidget.cc @@ -157,12 +157,18 @@ MapWidget::MapWidget(QWidget *parent) : zoomout->setStyleSheet(buttonStyle); createPath = new QPushButton(QIcon(":/images/actions/go-bottom.svg"), "", this); createPath->setStyleSheet(buttonStyle); + createPath->setToolTip(tr("Start / end waypoint add mode")); + createPath->setStatusTip(tr("Start / end waypoint add mode")); // clearTracking = new QPushButton(QIcon(""), "", this); // clearTracking->setStyleSheet(buttonStyle); followgps = new QPushButton(QIcon(":/images/actions/system-lock-screen.svg"), "", this); followgps->setStyleSheet(buttonStyle); + followgps->setToolTip(tr("Follow the position of the current MAV with the map center")); + followgps->setStatusTip(tr("Follow the position of the current MAV with the map center")); QPushButton* goToButton = new QPushButton(QIcon(""), "T", this); goToButton->setStyleSheet(buttonStyle); + goToButton->setToolTip(tr("Enter a latitude/longitude position to move the map to")); + goToButton->setStatusTip(tr("Enter a latitude/longitude position to move the map to")); zoomin->setMaximumWidth(30); zoomout->setMaximumWidth(30); -- 2.22.0