Browse Source

Implement message driven receiver pairing

QGC4.4
Jean Cyr 12 years ago
parent
commit
51e21f9f7f
  1. 11
      src/uas/UAS.cc
  2. 3
      src/uas/UAS.h
  3. 2
      src/uas/UASInterface.h
  4. 11
      src/ui/QGCPX4VehicleConfig.cc

11
src/uas/UAS.cc

@ -2867,6 +2867,17 @@ void UAS::land() @@ -2867,6 +2867,17 @@ void UAS::land()
}
/**
* 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
* and might differ between systems.
*/

3
src/uas/UAS.h

@ -723,6 +723,9 @@ public slots: @@ -723,6 +723,9 @@ public slots:
void home();
/** @brief Order the robot to land **/
void land();
/** @brief Order the robot to pair its receiver **/
void pairRX(int rxType, int rxSubType);
void halt();
void go();

2
src/uas/UASInterface.h

@ -290,6 +290,8 @@ public slots: @@ -290,6 +290,8 @@ public slots:
virtual void home() = 0;
/** @brief Order the robot to land **/
virtual void land() = 0;
/** @brief Order the robot to pair its receiver **/
virtual void pairRX(int rxType, int rxSubType) = 0;
/** @brief Halt the system */
virtual void halt() = 0;
/** @brief Start/continue the current robot action */

11
src/ui/QGCPX4VehicleConfig.cc

@ -343,15 +343,12 @@ void QGCPX4VehicleConfig::toggleSpektrumPairing(bool enabled) @@ -343,15 +343,12 @@ void QGCPX4VehicleConfig::toggleSpektrumPairing(bool enabled)
warnMsgBox.setStandardButtons(QMessageBox::Ok);
warnMsgBox.setDefaultButton(QMessageBox::Ok);
(void)warnMsgBox.exec();
return;
}
int mode = 1; // DSM2
if (ui->dsmxRadioButton->isChecked())
mode = 2; // DSMX
mav->getParamManager()->setPendingParam(0, "RC_DSM_BIND", mode, true);
// Do not save this parameter, just set in RAM
mav->getParamManager()->sendPendingParameters(false, true);
UASInterface* mav = UASManager::instance()->getActiveUAS();
if (mav)
mav->pairRX(0, ui->dsmxRadioButton->isChecked() ? 1 : 0);
}
void QGCPX4VehicleConfig::setTrimPositions()

Loading…
Cancel
Save