diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index e2bac965b57b0cc7f069c8323920183d5f1d1477..8a719dc5e36222335cfc97a3ba346c53ddbf019f 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1838,19 +1838,6 @@ bool Vehicle::xConfigMotors(void) return _firmwarePlugin->multiRotorXConfig(this); } -/* - * Internal - */ - -QString Vehicle::getMavIconColor() -{ - // TODO: Not using because not only the colors are ghastly, it doesn't respect dark/light palette - if(_mav) - return _mav->getColor().name(); - else - return QString("black"); -} - QString Vehicle::formatedMessages() { QString messages; diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 735280c35603e48203a62eaf9ad34184f16ceb0c..6d927d7ad635c7ed188ad5fcadcf34d8a75c0c6f 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -556,8 +556,6 @@ public: /// @return -1: reserver all buttons, >0 number of buttons to reserve Q_PROPERTY(int manualControlReservedButtonCount READ manualControlReservedButtonCount CONSTANT) - Q_INVOKABLE QString getMavIconColor(); - // Called when the message drop-down is invoked to clear current count Q_INVOKABLE void resetMessages(); diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index ea5c8f8148f4f7142f6c6e584b6f16ba784f5e54..f65a7fed7e03805a8170c81e69ad36871ab4f13f 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -1064,7 +1064,7 @@ void QGCXPlaneLink::setRandomPosition() _vehicle->altitudeAMSL()->rawValue().toDouble() + offAlt, _vehicle->roll()->rawValue().toDouble(), _vehicle->pitch()->rawValue().toDouble(), - _vehicle->uas()->getYaw()); + _vehicle->heading()->rawValue().toDouble()); } void QGCXPlaneLink::setRandomAttitude() diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 039d373faffd67703e203be8304399b33fe28531..cec9a70b7f08b274998d6e675772e309ad9efc1d 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -73,10 +73,6 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi attitudeStamped(false), lastAttitude(0), - roll(0.0), - pitch(0.0), - yaw(0.0), - imagePackets(0), // We must initialize to 0, otherwise extended data packets maybe incorrectly thought to be images blockHomePositionChanges(false), @@ -133,7 +129,6 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi #ifndef __mobile__ connect(_vehicle, &Vehicle::mavlinkMessageReceived, &fileManager, &FileManager::receiveMessage); - color = UASInterface::getNextColor(); #endif } diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 421941a52d7531daf7ff9b274712c6b79525289c..92cb0cf1623901a33e1a16b80be566e837b6a386 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -60,46 +60,9 @@ public: /** @brief The time interval the robot is switched on */ quint64 getUptime() const; - 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) - - /// Vehicle is about to go away - void shutdownVehicle(void); - - void setRoll(double val) - { - roll = val; - emit rollChanged(val,"roll"); - } - - double getRoll() const - { - return roll; - } - - void setPitch(double val) - { - pitch = val; - emit pitchChanged(val,"pitch"); - } - - double getPitch() const - { - return pitch; - } - - void setYaw(double val) - { - yaw = val; - emit yawChanged(val,"yaw"); - } - - double getYaw() const - { - return yaw; - } - + /// Vehicle is about to go away + void shutdownVehicle(void); + // Setters for HIL noise variance void setXaccVar(float var){ xacc_var = var; @@ -196,9 +159,6 @@ protected: //COMMENTS FOR TEST UNIT bool attitudeKnown; ///< True if attitude was received, false else bool attitudeStamped; ///< Should arriving data be timestamped with the last attitude? This helps with broken system time clocks on the MAV quint64 lastAttitude; ///< Timestamp of last attitude measurement - double roll; - double pitch; - double yaw; // dongfang: This looks like a candidate for being moved off to a separate class. /// IMAGING diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index bd162d1c603c07c253b0996f9f9cf8c96b6ef133..ffee6b2f6af55657a173572dc4698b7209a4127a 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -45,62 +45,12 @@ public: /** @brief The time interval the robot is switched on **/ virtual quint64 getUptime() const = 0; - virtual double getRoll() const = 0; - virtual double getPitch() const = 0; - virtual double getYaw() const = 0; - #ifndef __mobile__ virtual FileManager* getFileManager() = 0; #endif - /** - * @brief Get the color for this UAS - * - * This static function holds a color map that allows to draw a new color for each robot - * - * @return The next color in the color map. The map holds 20 colors and starts from the beginning - * if the colors are exceeded. - */ -#if !defined(__mobile__) - static QColor getNextColor() { - /* Create color map */ - static QList colors = QList() - << QColor(231,72,28) - << QColor(104,64,240) - << QColor(203,254,121) - << QColor(161,252,116) - << QColor(232,33,47) - << QColor(116,251,110) - << QColor(234,38,107) - << QColor(104,250,138) - << QColor(235,43,165) - << QColor(98,248,176) - << QColor(236,48,221) - << QColor(92,247,217) - << QColor(200,54,238) - << QColor(87,231,246) - << QColor(151,59,239) - << QColor(81,183,244) - << QColor(75,133,243) - << QColor(242,255,128) - << QColor(230,126,23); - - static int nextColor = -1; - if(nextColor == 18){//if at the end of the list - nextColor = -1;//go back to the beginning - } - nextColor++; - return colors[nextColor];//return the next color - } -#endif - virtual QMap getComponents() = 0; - QColor getColor() - { - return color; - } - enum StartCalibrationType { StartCalibrationRadio, StartCalibrationGyro, @@ -160,9 +110,6 @@ public slots: /** @brief Send command to disable all bindings/maps between RC and parameters */ virtual void unsetRCToParameterMap() = 0; -protected: - QColor color; - signals: /** @brief A text message from the system has been received */ void textMessageReceived(int uasid, int componentid, int severity, QString text);