Commit 51e21f9f authored by Jean Cyr's avatar Jean Cyr

Implement message driven receiver pairing

parent 341c7719
...@@ -2866,6 +2866,17 @@ void UAS::land() ...@@ -2866,6 +2866,17 @@ void UAS::land()
sendMessage(msg); sendMessage(msg);
} }
/**
* Order the robot to land on the runway
*/
void UAS::pairRX(int rxType, int rxSubType)
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_START_RX_PAIR, 0, rxType, rxSubType, 0, 0, 0, 0, 0);
sendMessage(msg);
}
/** /**
* The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
* and might differ between systems. * and might differ between systems.
......
...@@ -723,6 +723,9 @@ public slots: ...@@ -723,6 +723,9 @@ public slots:
void home(); void home();
/** @brief Order the robot to land **/ /** @brief Order the robot to land **/
void land(); void land();
/** @brief Order the robot to pair its receiver **/
void pairRX(int rxType, int rxSubType);
void halt(); void halt();
void go(); void go();
......
...@@ -290,6 +290,8 @@ public slots: ...@@ -290,6 +290,8 @@ public slots:
virtual void home() = 0; virtual void home() = 0;
/** @brief Order the robot to land **/ /** @brief Order the robot to land **/
virtual void land() = 0; virtual void land() = 0;
/** @brief Order the robot to pair its receiver **/
virtual void pairRX(int rxType, int rxSubType) = 0;
/** @brief Halt the system */ /** @brief Halt the system */
virtual void halt() = 0; virtual void halt() = 0;
/** @brief Start/continue the current robot action */ /** @brief Start/continue the current robot action */
......
...@@ -343,15 +343,12 @@ void QGCPX4VehicleConfig::toggleSpektrumPairing(bool enabled) ...@@ -343,15 +343,12 @@ void QGCPX4VehicleConfig::toggleSpektrumPairing(bool enabled)
warnMsgBox.setStandardButtons(QMessageBox::Ok); warnMsgBox.setStandardButtons(QMessageBox::Ok);
warnMsgBox.setDefaultButton(QMessageBox::Ok); warnMsgBox.setDefaultButton(QMessageBox::Ok);
(void)warnMsgBox.exec(); (void)warnMsgBox.exec();
return;
} }
int mode = 1; // DSM2 UASInterface* mav = UASManager::instance()->getActiveUAS();
if (ui->dsmxRadioButton->isChecked()) if (mav)
mode = 2; // DSMX mav->pairRX(0, ui->dsmxRadioButton->isChecked() ? 1 : 0);
mav->getParamManager()->setPendingParam(0, "RC_DSM_BIND", mode, true);
// Do not save this parameter, just set in RAM
mav->getParamManager()->sendPendingParameters(false, true);
} }
void QGCPX4VehicleConfig::setTrimPositions() void QGCPX4VehicleConfig::setTrimPositions()
......
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