From 124997d0b55db8d119583cf614224a32db0b01fa Mon Sep 17 00:00:00 2001 From: pixhawk Date: Sun, 4 Apr 2010 19:11:10 +0200 Subject: [PATCH] Minor UI improvements, pushed implementation of some UI elements --- images/style-mission.css | 39 +++----------- src/comm/MAVLinkSimulationLink.cc | 6 ++- src/uas/UAS.cc | 86 ------------------------------- src/ui/HUD.cc | 2 +- src/ui/UASControl.ui | 10 +++- src/ui/uas/UASControlWidget.cc | 28 +++++----- src/ui/uas/UASControlWidget.h | 3 ++ 7 files changed, 40 insertions(+), 134 deletions(-) diff --git a/images/style-mission.css b/images/style-mission.css index 8435374db..10a8a3cdc 100644 --- a/images/style-mission.css +++ b/images/style-mission.css @@ -88,7 +88,8 @@ QDockWidget::close-button, QDockWidget::float-button { QDockWidget::title { text-align: left; - background: #222224; + background: #121214; + color: #4A4A4F; padding-left: 5px; height: 10px; border-bottom: 1px solid #555555; @@ -194,24 +195,24 @@ QPushButton:checked#controlButton { } QProgressBar { - border: 1px solid #EEEEEE; + border: 1px solid #4A4A4F; border-radius: 4px; text-align: center; padding: 2px; - color: white; + color: #DDDDDF; background-color: #111118; } QProgressBar:horizontal { - height 12px; + height: 9px; } QProgressBar:vertical { - width 12px; + width: 9px; } QProgressBar::chunk { - background-color: #656565; + background-color: #3C7B9E; } QProgressBar::chunk#batteryBar { @@ -224,28 +225,4 @@ QProgressBar::chunk#speedBar { QProgressBar::chunk#thrustBar { background-color: orange; -} - -QProgressBar::chunk#bandwidthBar { - background-color: orange; -} -QProgressBar::chunk#loadBar { - background-color: yellow; -} - -QProgressBar::chunk#topRotorBar { - background-color: yellow; -} - -QProgressBar::chunk#botRotorBar { - background-color: yellow; -} - -QProgressBar::chunk#leftServoBar { - background-color: #99BFDD; -} - -QProgressBar::chunk#rightServoBar -{ - background-color: blue; -} +} diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index a45cc4aa1..89622d498 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -484,7 +484,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) status.mode = MAV_MODE_AUTO; break; case MAV_ACTION_RETURN: - + status.status = MAV_STATE_LANDING; break; case MAV_ACTION_MOTORS_START: status.status = MAV_STATE_ACTIVE; @@ -498,6 +498,10 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) status.status = MAV_STATE_EMERGENCY; status.mode = MAV_MODE_MANUAL; break; + case MAV_ACTION_SHUTDOWN: + status.status = MAV_STATE_POWEROFF; + status.mode = MAV_MODE_LOCKED; + break; } } break; diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 20d53fc4d..de06e8ece 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -157,92 +157,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit voltageChanged(message.sysid, state.vbat/1000.0f); } break; - /* - case MAVLINK_MSG_ID_SYSTEM: - // std::cerr << std::endl; - // std::cerr << "System Message received" << std::endl; - currentVoltage = message_system_get_voltage(message.payload)/1000.0f; - filterVoltage(currentVoltage); - if (startVoltage == 0) startVoltage = currentVoltage; - timeRemaining = calculateTimeRemaining(); - //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining; - emit batteryChanged(this, filterVoltage(), getChargeLevel(), timeRemaining); - - emit voltageChanged(message.acid, message_system_get_voltage(message.payload)/1000.0f); - emit loadChanged(this, message_system_get_cpu_usage(message.payload)/100.0f); - emit valueChanged(uasId, "Battery", message_system_get_voltage(message.payload), MG::TIME::getGroundTimeNow()); - emit valueChanged(uasId, "CPU Load", message_system_get_cpu_usage(message.payload), MG::TIME::getGroundTimeNow()); - break; - case MAVLINK_MSG_ID_ACTUATORS: - emit actuatorChanged(this, 0, message_actuator_get_act1(message.payload)); - emit valueChanged(this->getUASID(), "Top Rotor", message_actuator_get_act1(message.payload), MG::TIME::getGroundTimeNow()); - emit actuatorChanged(this, 1, message_actuator_get_act2(message.payload)); - emit valueChanged(this->getUASID(), "Bottom Rotor", message_actuator_get_act2(message.payload), MG::TIME::getGroundTimeNow()); - emit actuatorChanged(this, 2, message_actuator_get_act3(message.payload)); - emit valueChanged(this->getUASID(), "Left Servo", message_actuator_get_act3(message.payload), MG::TIME::getGroundTimeNow()); - emit actuatorChanged(this, 3, message_actuator_get_act4(message.payload)); - emit valueChanged(this->getUASID(), "Right Servo", message_actuator_get_act4(message.payload), MG::TIME::getGroundTimeNow()); - // Calculate thrust sum - thrustSum = (message_actuator_get_act1(message.payload) + message_actuator_get_act2(message.payload)) / 2; - emit thrustChanged(this, thrustSum); - break; - case MAVLINK_MSG_ID_STATE: - emit valueChanged(uasId, "State", message_state_get_state(message.payload), MG::TIME::getGroundTimeNow()); - getStatusForCode(message_state_get_state(message.payload), uasState, stateDescription); - emit statusChanged(this, uasState, stateDescription); - break; - case MAVLINK_MSG_ID_POSITION: - // Position message is displayed in meters and degrees - { - quint64 time = MG::TIME::getGroundTimeNow();//message_position_get_msec(message.payload); - emit valueChanged(this, "x", message_position_get_posX(message.payload), time); - emit valueChanged(this, "y", message_position_get_posY(message.payload), time); - emit valueChanged(this, "z", message_position_get_posZ(message.payload), time); - emit valueChanged(this, "roll", message_position_get_roll(message.payload), time); - emit valueChanged(this, "pitch", message_position_get_pitch(message.payload), time); - emit valueChanged(this, "yaw", message_position_get_yaw(message.payload), time); - emit valueChanged(this, "x speed", message_position_get_speedX(message.payload), time); - emit valueChanged(this, "y speed", message_position_get_speedY(message.payload), time); - emit valueChanged(this, "z speed", message_position_get_speedZ(message.payload), time); - emit valueChanged(this, "roll speed", message_position_get_speedRoll(message.payload), time); - emit valueChanged(this, "pitch speed", message_position_get_speedPitch(message.payload), time); - emit valueChanged(this, "yaw speed", message_position_get_speedYaw(message.payload), time); - - emit localPositionChanged(this, message_position_get_posX(message.payload), message_position_get_posY(message.payload), message_position_get_posZ(message.payload), time); - emit valueChanged(uasId, "x", message_position_get_posX(message.payload), time); - emit valueChanged(uasId, "y", message_position_get_posY(message.payload), time); - emit valueChanged(uasId, "z", message_position_get_posZ(message.payload), time); - emit valueChanged(uasId, "roll", message_position_get_roll(message.payload), time); - emit valueChanged(uasId, "pitch", message_position_get_pitch(message.payload), time); - emit valueChanged(uasId, "yaw", message_position_get_yaw(message.payload), time); - emit valueChanged(uasId, "x speed", message_position_get_speedX(message.payload), time); - emit valueChanged(uasId, "y speed", message_position_get_speedY(message.payload), time); - emit valueChanged(uasId, "z speed", message_position_get_speedZ(message.payload), time); - emit valueChanged(uasId, "roll speed", message_position_get_speedRoll(message.payload), time); - emit valueChanged(uasId, "pitch speed", message_position_get_speedPitch(message.payload), time); - emit valueChanged(uasId, "yaw speed", message_position_get_speedYaw(message.payload), time); - } - break; - case MAVLINK_MSG_ID_MARKER: - emit valueChanged(uasId, "marker confidence", message_marker_get_confidence(message.payload), MG::TIME::getGroundTimeNow()); - emit valueChanged(uasId, "marker x", message_marker_get_posX(message.payload), MG::TIME::getGroundTimeNow()); - emit valueChanged(uasId, "marker y", message_marker_get_posY(message.payload), MG::TIME::getGroundTimeNow()); - emit valueChanged(uasId, "marker z", message_marker_get_posZ(message.payload), MG::TIME::getGroundTimeNow()); - emit valueChanged(uasId, "marker roll", message_marker_get_roll(message.payload)/M_PI*180.0f, MG::TIME::getGroundTimeNow()); - emit valueChanged(uasId, "marker pitch", message_marker_get_pitch(message.payload)/M_PI*180.0f, MG::TIME::getGroundTimeNow()); - emit valueChanged(uasId, "marker yaw", message_marker_get_yaw(message.payload)/M_PI*180.0f, MG::TIME::getGroundTimeNow()); - break; - case MAVLINK_MSG_ID_IMAGE: - //std::cerr << std::endl; - //std::cerr << "IMAGE DATA RECEIVED" << std::endl; - emit imageStarted(message_image_get_rid(message.payload), message_image_get_width(message.payload), message_image_get_height(message.payload), message_image_get_depth(message.payload), message_image_get_channels(message.payload)); - break; - case MAVLINK_MSG_ID_BYTES: - //std::cerr << std::endl; - //std::cerr << "BYTES RESSOURCE RECEIVED" << std::endl; - emit imageDataReceived(message_bytestream_get_rid(message.payload), message_bytestream_get_data(message.payload), message_bytestream_get_length(message.payload), message_bytestream_get_index(message.payload)); - break; - */ case MAVLINK_MSG_ID_RAW_IMU: { raw_imu_t raw; diff --git a/src/ui/HUD.cc b/src/ui/HUD.cc index 3e31ee282..77426479e 100644 --- a/src/ui/HUD.cc +++ b/src/ui/HUD.cc @@ -190,7 +190,7 @@ void HUD::updateValue(UASInterface* uas, QString name, double value, quint64 mse lastUpdate.insert(name, msec); //} - qDebug() << __FILE__ << __LINE__ << "VALUE:" << value << "MEAN:" << mean << "DOT:" << dot << "COUNT:" << meanCount; + //qDebug() << __FILE__ << __LINE__ << "VALUE:" << value << "MEAN:" << mean << "DOT:" << dot << "COUNT:" << meanCount; } } diff --git a/src/ui/UASControl.ui b/src/ui/UASControl.ui index 9f31b626c..7ce5c3e33 100644 --- a/src/ui/UASControl.ui +++ b/src/ui/UASControl.ui @@ -6,8 +6,8 @@ 0 0 - 395 - 215 + 387 + 212 @@ -17,6 +17,9 @@ 20 + + 6 + @@ -128,6 +131,9 @@ No actions executed so far + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + diff --git a/src/ui/uas/UASControlWidget.cc b/src/ui/uas/UASControlWidget.cc index 4efba1f4d..41375f29b 100644 --- a/src/ui/uas/UASControlWidget.cc +++ b/src/ui/uas/UASControlWidget.cc @@ -64,13 +64,9 @@ void UASControlWidget::setUAS(UASInterface* uas) disconnect(ui.controlButton, SIGNAL(clicked()), uas, SLOT(enable_motors())); disconnect(ui.liftoffButton, SIGNAL(clicked()), uas, SLOT(launch())); disconnect(ui.landButton, SIGNAL(clicked()), uas, SLOT(home())); - //disconnect(ui.haltButton, SIGNAL(clicked()), uas, SLOT(halt())); - //disconnect(ui.continueButton, SIGNAL(clicked()), uas, SLOT(go())); - //disconnect(ui.forceLandButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP())); disconnect(ui.shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown())); - //disconnect(uas, SIGNAL(autoModeChanged(bool)), ui.autoButton, SLOT(setChecked(bool))); - //disconnect(ui.autoButton, SIGNAL(clicked(bool)), uas, SLOT(setAutoMode(bool))); - //disconnect(ui.motorsStopButton, SIGNAL(clicked()), uas, SLOT(disable_motors())); + disconnect(ui.modeComboBox, SIGNAL(activated(int)), this, SLOT(setMode(int))); + disconnect(ui.setModeButton, SIGNAL(clicked()), this, SLOT(transmitMode())); } else { @@ -78,14 +74,9 @@ void UASControlWidget::setUAS(UASInterface* uas) connect(ui.controlButton, SIGNAL(clicked()), this, SLOT(cycleContextButton())); connect(ui.liftoffButton, SIGNAL(clicked()), uas, SLOT(launch())); connect(ui.landButton, SIGNAL(clicked()), uas, SLOT(home())); - //connect(ui.haltButton, SIGNAL(clicked()), uas, SLOT(halt())); - //connect(ui.continueButton, SIGNAL(clicked()), uas, SLOT(go())); - //connect(ui.forceLandButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP())); connect(ui.shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown())); - //connect(ui.autoButton, SIGNAL(clicked(bool)), uas, SLOT(setAutoMode(bool))); - //connect(uas, SIGNAL(autoModeChanged(bool)), ui.autoButton, SLOT(setChecked(bool))); - //connect(ui.motorsStopButton, SIGNAL(clicked()), uas, SLOT(disable_motors())); connect(ui.modeComboBox, SIGNAL(activated(int)), this, SLOT(setMode(int))); + connect(ui.setModeButton, SIGNAL(clicked()), this, SLOT(transmitMode())); ui.modeComboBox->insertItem(0, "Select.."); ui.controlStatusLabel->setText(tr("Connected to ") + uas->getUASName()); @@ -100,6 +91,7 @@ UASControlWidget::~UASControlWidget() { void UASControlWidget::setMode(int mode) { + // Adapt context button mode switch (mode) { case MAV_MODE_LOCKED: @@ -119,7 +111,17 @@ void UASControlWidget::setMode(int mode) } // Set mode on system - if (mode >= MAV_MODE_LOCKED && mode <= MAV_MODE_TEST3) this->uas->setMode(mode); + if (mode >= MAV_MODE_LOCKED && mode <= MAV_MODE_TEST3) + { + uasMode = mode; + ui.modeComboBox->setCurrentIndex(mode); + } + qDebug() << "SET MODE REQUESTED" << mode; +} + +void UASControlWidget::transmitMode() +{ + this->uas->setMode(uasMode); } void UASControlWidget::cycleContextButton() diff --git a/src/ui/uas/UASControlWidget.h b/src/ui/uas/UASControlWidget.h index abedbdcc7..efb892efe 100644 --- a/src/ui/uas/UASControlWidget.h +++ b/src/ui/uas/UASControlWidget.h @@ -53,9 +53,12 @@ public slots: void cycleContextButton(); /** @brief Set the operation mode of the MAV */ void setMode(int mode); + /** @brief Transmit the operation mode **/ + void transmitMode(); protected: UASInterface* uas; + int uasMode; private: Ui::uasControl ui; -- 2.22.0