diff --git a/src/uas/SlugsMAV.cc b/src/uas/SlugsMAV.cc index 0831479456c1e80f8f852def492aa08b030ea4f5..cd0e4457f5b85cc82f5b0c44a722ad0b344dc31c 100644 --- a/src/uas/SlugsMAV.cc +++ b/src/uas/SlugsMAV.cc @@ -135,11 +135,11 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) break; case MAVLINK_MSG_ID_MID_LVL_CMDS: //180 - + mavlink_msg_mid_lvl_cmds_decode(&message, &mlMidLevelCommands); break; case MAVLINK_MSG_ID_CTRL_SRFC_PT: //181 - + mavlink_msg_ctrl_srfc_pt_decode(&message, &mlPassthrough); break; case MAVLINK_MSG_ID_PID: //182 diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 7cb68436b7268b7927fcdc4ac83e0fe4bcd919ed..5973ad4e8ca154c186440e1cc587626edfa9de68 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -625,6 +625,7 @@ void MainWindow::buildSlugsWidgets() addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget(bool)), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea); } + // if (!slugsCamControlWidget) // { // slugsCamControlWidget = new QDockWidget(tr("Slugs Video Camera Control"), this); @@ -1017,11 +1018,6 @@ void MainWindow::connectCommonWidgets() connect(waypointsDockWidget->widget(), SIGNAL(changePointList()), mapWidget, SLOT(clearWaypoints())); } - if(controlDockWidget && controlParameterWidget) - { - connect(controlDockWidget->widget(), SIGNAL(changedMode(int)), controlParameterWidget->widget(), SLOT(changedMode(int))); - } - //TODO temporaly debug if (slugsHilSimWidget && slugsHilSimWidget->widget()){ connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), @@ -1032,6 +1028,11 @@ void MainWindow::connectCommonWidgets() connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), controlParameterWidget->widget(), SLOT(activeUasSet(UASInterface*))); } + + if(controlDockWidget && controlParameterWidget) + { + connect(controlDockWidget->widget(), SIGNAL(changedMode(int)), controlParameterWidget->widget(), SLOT(changedMode(int))); + } } void MainWindow::createCustomWidget() diff --git a/src/ui/UASControlParameters.ui b/src/ui/UASControlParameters.ui index da71391b74bc16ecf08348e64d0a237ccc28caa6..dff5014ef15d9420bf846eac5b48e1cc5b2b656e 100644 --- a/src/ui/UASControlParameters.ui +++ b/src/ui/UASControlParameters.ui @@ -6,8 +6,8 @@ 0 0 - 200 - 228 + 204 + 246 @@ -26,6 +26,58 @@ Form + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 100 + 0 + + + + + 16777215 + 16777215 + + + + ---- + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + @@ -36,61 +88,9 @@ - Tab 1 + Commands - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 100 - 0 - - - - - 16777215 - 16777215 - - - - ---- - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - @@ -180,8 +180,98 @@ - Tab 2 + Passthrough + + + + + + + + + Elevator + + + + + + + Rudder + + + + + + + Throttle + + + + + + + Ailerons + + + + + + + + + + + Right Aileron + + + + + + + Right Elevator + + + + + + + Left Flap + + + + + + + Right Flap + + + + + + + + + + + Set + + + + + + + Qt::Vertical + + + + 20 + 26 + + + + + diff --git a/src/ui/uas/UASControlParameters.cpp b/src/ui/uas/UASControlParameters.cpp index 742bffd4258da79eb59d6b6ea69dc3799de3b293..6cf3414e0a5e346c4b16c612c0d9b067fd156cd8 100644 --- a/src/ui/uas/UASControlParameters.cpp +++ b/src/ui/uas/UASControlParameters.cpp @@ -27,14 +27,9 @@ UASControlParameters::UASControlParameters(QWidget *parent) : { ui->setupUi(this); - //this->mode = "MAV_MODE_UNKNOWN"; - //connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUasSet(UASInterface*))); - connect(ui->btGetCommands, SIGNAL(clicked()), this, SLOT(getCommands())); - //QColor groupColor = QColor(231,72,28); - //QString borderColor = "#FA4A4F"; - //groupColor = groupColor.darker(475); + connect(ui->btSetCtrl, SIGNAL(clicked()), this, SLOT(setPassthrough())); } UASControlParameters::~UASControlParameters() @@ -46,46 +41,48 @@ void UASControlParameters::changedMode(int mode) { QString modeTemp; - if (mode == CONTROL_MODE_LOCKED_INDEX) - { - modeTemp= CONTROL_MODE_LOCKED; - } - else if (mode == CONTROL_MODE_MANUAL_INDEX) - { - modeTemp= CONTROL_MODE_MANUAL; - } - else if (mode == CONTROL_MODE_GUIDED_INDEX) - { - modeTemp= CONTROL_MODE_GUIDED; - } - else if (mode == CONTROL_MODE_AUTO_INDEX) - { - modeTemp= CONTROL_MODE_AUTO; - } - else if (mode == CONTROL_MODE_TEST1_INDEX) - { - modeTemp= CONTROL_MODE_TEST1; - } - else if (mode == CONTROL_MODE_TEST2_INDEX) - { - modeTemp= CONTROL_MODE_TEST2; - } - else if (mode == CONTROL_MODE_TEST3_INDEX) - { - modeTemp= CONTROL_MODE_TEST3; - } - else if (mode == CONTROL_MODE_RC_TRAINING_INDEX) + switch (mode) { - modeTemp= CONTROL_MODE_RC_TRAINING; + case (uint8_t)MAV_MODE_LOCKED: + modeTemp = "LOCKED MODE"; + break; + case (uint8_t)MAV_MODE_MANUAL: + modeTemp = "MANUAL MODE"; + break; + case (uint8_t)MAV_MODE_AUTO: + modeTemp = "AUTO MODE"; + break; + case (uint8_t)MAV_MODE_GUIDED: + modeTemp = "GUIDED MODE"; + break; + case (uint8_t)MAV_MODE_READY: + modeTemp = "READY MODE"; + break; + case (uint8_t)MAV_MODE_TEST1: + modeTemp = "TEST1 MODE"; + break; + case (uint8_t)MAV_MODE_TEST2: + modeTemp = "TEST2 MODE"; + break; + case (uint8_t)MAV_MODE_TEST3: + modeTemp = "TEST3 MODE"; + break; + case (uint8_t)MAV_MODE_RC_TRAINING: + modeTemp = "RC TRAINING MODE"; + break; + default: + modeTemp = "UNINIT MODE"; + break; } - if( static_cast(modeTemp) != this->mode) + + if(modeTemp != this->mode) { ui->lbMode->setStyleSheet("background-color: rgb(255, 0, 0)"); } else { - ui->lbMode->setStyleSheet(""); + ui->lbMode->setStyleSheet("background-color: rgb(0, 255, 0)"); } } @@ -94,8 +91,12 @@ void UASControlParameters::activeUasSet(UASInterface *uas) connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(speedChanged(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64))); + connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString))); + connect(uas, SIGNAL(thrustChanged(UASInterface*,double)), this, SLOT(thrustChanged(UASInterface*,double)) ); + //connect(uas, SIGNAL(radioCalibrationReceived(QPointer)), this, SLOT(radioChanged(QPointer))); + activeUAS= uas; } @@ -120,7 +121,18 @@ void UASControlParameters::updateAttitude(UASInterface *uas, double roll, double } void UASControlParameters::setCommands() -{} +{ + UAS* myUas= static_cast(this->activeUAS); + + mavlink_message_t msg; + + tempCmds.uCommand = ui->sbAirSpeed->value(); + tempCmds.hCommand = ui->sbHeight->value(); + tempCmds.rCommand = ui->sbTurnRate->value(); + + mavlink_msg_mid_lvl_cmds_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &this->tempCmds); + myUas->sendMessage(msg); +} void UASControlParameters::getCommands() { @@ -129,10 +141,91 @@ void UASControlParameters::getCommands() ui->sbTurnRate->setValue(this->roll); } +void UASControlParameters::setPassthrough() +{ + //UAS* myUas= static_cast(this->activeUAS); + + //mavlink_message_t msg; + + int8_t tmpBit=0; + + if(ui->cxAilerons->isChecked()) + { + tmpBit+=1; + } + if(ui->cxElevator->isChecked()) + { + tmpBit+=2; + } + if(ui->cxLeftFlap->isChecked()) + { + tmpBit+=4; + } + if(ui->cxRightAileron->isChecked()) + { + tmpBit+=8; + } + if(ui->cxRightElevator->isChecked()) + { + tmpBit+=16; + } + if(ui->cxRightFlap->isChecked()) + { + tmpBit+=32; + } + if(ui->cxRudder->isChecked()) + { + tmpBit+=64; + } + if(ui->cxThrottle->isChecked()) + { + tmpBit+=128; + } + + generic_16bit r; + r.b[1] = 0; + r.b[0] = tmpBit;//255; + + tempCtrl.bitfieldPt= (uint16_t)r.s; + + //mavlink_msg_ctrl_srfc_pt_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &this->tempCtrl); + //myUas->sendMessage(msg); + qDebug()<mode = mode; ui->lbMode->setText(this->mode); + + ui->lbMode->setStyleSheet("background-color: rgb(0, 255, 0)"); +} + +void UASControlParameters::thrustChanged(UASInterface *uas, double throttle) +{ + Q_UNUSED(uas); + this->throttle= throttle; +} + + +void UASControlParameters::radioChanged(const QPointer& radio) +{ + if (radio) + { + if (this->radio) + { + delete this->radio; + } + + this->radio = new RadioCalibrationData(*radio); + +// aileron->set((*radio)(RadioCalibrationData::AILERON)); +// elevator->set((*radio)(RadioCalibrationData::ELEVATOR)); +// rudder->set((*radio)(RadioCalibrationData::RUDDER)); +// gyro->set((*radio)(RadioCalibrationData::GYRO)); +// pitch->set((*radio)(RadioCalibrationData::PITCH)); +// throttle->set((*radio)(RadioCalibrationData::THROTTLE)); + } } diff --git a/src/ui/uas/UASControlParameters.h b/src/ui/uas/UASControlParameters.h index 25cc456cc991e16af8d86ffbf2c12d6c1735010b..7051cdbb1ac72c7b73001540744f8adab7ea90e5 100644 --- a/src/ui/uas/UASControlParameters.h +++ b/src/ui/uas/UASControlParameters.h @@ -27,7 +27,11 @@ public slots: void updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 time); void setCommands(); void getCommands(); + + void setPassthrough(); void updateMode(int uas,QString mode,QString description); + void thrustChanged(UASInterface* uas,double throttle); + void radioChanged(const QPointer& radio); private: Ui::UASControlParameters *ui; @@ -36,8 +40,13 @@ private: double speed; double roll; double altitude; + double throttle; QString mode; QString REDcolorStyle; + QPointer radio; + LinkInterface* hilLink; + mavlink_mid_lvl_cmds_t tempCmds; + mavlink_ctrl_srfc_pt_t tempCtrl; }; #endif // UASCONTROLPARAMETERS_H