Commit 65f16374 authored by Michael Carpenter's avatar Michael Carpenter
Browse files

Changes for new calibration in APM 3.0 (Re:...

Changes for new calibration in APM 3.0 (Re: https://github.com/diydrones/MissionPlanner/issues/38), and change in some of the serial timeouts
parent 9c270151
[PX4%20Calibration%20Tool]
QGC_TOOL_WIDGET_ITEMS\1\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_DESCRIPTION=Reboot (only in standby)
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_BUTTONTEXT=REBOOT
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_COMMANDID=246
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM1=1
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM2=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\2\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=Magnetometer calibration
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_BUTTONTEXT=MAG
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM1=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM2=1
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\3\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_DESCRIPTION=Accelerometer calibration
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_BUTTONTEXT=ACCEL
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM1=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM2=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM5=1
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\4\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_BUTTONTEXT=GYRO
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM1=1
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM2=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\5\QGC_COMMAND_BUTTON_DESCRIPTION=RC Trim calibration
QGC_TOOL_WIDGET_ITEMS\5\QGC_COMMAND_BUTTON_BUTTONTEXT=TRIM
QGC_TOOL_WIDGET_ITEMS\5\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\5\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\5\QGC_COMMAND_BUTTON_PARAM1=1
QGC_TOOL_WIDGET_ITEMS\5\QGC_COMMAND_BUTTON_PARAM2=0
QGC_TOOL_WIDGET_ITEMS\5\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\5\QGC_COMMAND_BUTTON_PARAM4=1
QGC_TOOL_WIDGET_ITEMS\5\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\5\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\5\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\size=5
...@@ -12,81 +12,27 @@ QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0 ...@@ -12,81 +12,27 @@ QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0 QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0 QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\2\TYPE=TEXT QGC_TOOL_WIDGET_ITEMS\2\TYPE=TEXT
QGC_TOOL_WIDGET_ITEMS\2\QGC_TEXT_SOURCE=NONE QGC_TOOL_WIDGET_ITEMS\2\QGC_TEXT_SOURCE=NONE
QGC_TOOL_WIDGET_ITEMS\2\QGC_TEXT_ID=MAG_LABEL QGC_TOOL_WIDGET_ITEMS\2\QGC_TEXT_ID=ACCEL_LABEL
QGC_TOOL_WIDGET_ITEMS\2\QGC_TEXT_TEXT= QGC_TOOL_WIDGET_ITEMS\2\QGC_TEXT_TEXT=
QGC_TOOL_WIDGET_ITEMS\3\TYPE=COMMANDBUTTON QGC_TOOL_WIDGET_ITEMS\3\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_DESCRIPTION=Magnetometer calibration QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_DESCRIPTION=Accelerometer calibration
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_BUTTONTEXT=MAG QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_BUTTONTEXT=ACCEL
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_COMMANDID=241 QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_LABEL=MAG_TEXT QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_LABEL=ACCEL_TEXT
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_RESPONSE=6
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM1=0 QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM1=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM2=1 QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM2=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM3=0 QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM4=0 QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM5=0 QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM5=1
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM6=0 QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM7=0 QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\4\TYPE=TEXT QGC_TOOL_WIDGET_ITEMS\4\TYPE=TEXT
QGC_TOOL_WIDGET_ITEMS\4\QGC_TEXT_SOURCE=MAV QGC_TOOL_WIDGET_ITEMS\4\QGC_TEXT_SOURCE=MAV
QGC_TOOL_WIDGET_ITEMS\4\QGC_TEXT_ID=MAG_TEXT QGC_TOOL_WIDGET_ITEMS\4\QGC_TEXT_ID=ACCEL_TEXT
QGC_TOOL_WIDGET_ITEMS\4\QGC_TEXT_TEXT= QGC_TOOL_WIDGET_ITEMS\4\QGC_TEXT_TEXT=
QGC_TOOL_WIDGET_ITEMS\size=4
QGC_TOOL_WIDGET_ITEMS\5\TYPE=TEXT
QGC_TOOL_WIDGET_ITEMS\5\QGC_TEXT_SOURCE=NONE
QGC_TOOL_WIDGET_ITEMS\5\QGC_TEXT_ID=ACCEL_LABEL
QGC_TOOL_WIDGET_ITEMS\5\QGC_TEXT_TEXT=
QGC_TOOL_WIDGET_ITEMS\6\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_DESCRIPTION=Accelerometer calibration
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_BUTTONTEXT=ACCEL
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_LABEL=ACCEL_TEXT
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_PARAM1=0
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_PARAM2=0
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_PARAM5=1
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\6\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\7\TYPE=TEXT
QGC_TOOL_WIDGET_ITEMS\7\QGC_TEXT_SOURCE=MAV
QGC_TOOL_WIDGET_ITEMS\7\QGC_TEXT_ID=ACCEL_TEXT
QGC_TOOL_WIDGET_ITEMS\7\QGC_TEXT_TEXT=
QGC_TOOL_WIDGET_ITEMS\8\TYPE=TEXT
QGC_TOOL_WIDGET_ITEMS\8\QGC_TEXT_SOURCE=NONE
QGC_TOOL_WIDGET_ITEMS\8\QGC_TEXT_ID=GYRO_LABEL
QGC_TOOL_WIDGET_ITEMS\8\QGC_TEXT_TEXT=
QGC_TOOL_WIDGET_ITEMS\9\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_BUTTONTEXT=GYRO
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_LABEL=GYRO_TEXT
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_PARAM1=1
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_PARAM2=0
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\9\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\10\TYPE=TEXT
QGC_TOOL_WIDGET_ITEMS\10\QGC_TEXT_SOURCE=MAV
QGC_TOOL_WIDGET_ITEMS\10\QGC_TEXT_ID=GYRO_TEXT
QGC_TOOL_WIDGET_ITEMS\10\QGC_TEXT_TEXT=
QGC_TOOL_WIDGET_ITEMS\11\QGC_COMMAND_BUTTON_DESCRIPTION=RC Trim calibration
QGC_TOOL_WIDGET_ITEMS\11\QGC_COMMAND_BUTTON_BUTTONTEXT=TRIM
QGC_TOOL_WIDGET_ITEMS\11\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\11\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\11\QGC_COMMAND_BUTTON_PARAM1=1
QGC_TOOL_WIDGET_ITEMS\11\QGC_COMMAND_BUTTON_PARAM2=0
QGC_TOOL_WIDGET_ITEMS\11\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\11\QGC_COMMAND_BUTTON_PARAM4=1
QGC_TOOL_WIDGET_ITEMS\11\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\11\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\11\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\size=11
...@@ -398,9 +398,11 @@ void SerialLink::run() ...@@ -398,9 +398,11 @@ void SerialLink::run()
// Qt way to make clear what a while(1) loop does // Qt way to make clear what a while(1) loop does
quint64 msecs = QDateTime::currentMSecsSinceEpoch(); quint64 msecs = QDateTime::currentMSecsSinceEpoch();
quint64 initialmsecs = QDateTime::currentMSecsSinceEpoch();
quint64 bytes = 0; quint64 bytes = 0;
bool triedreset = false; bool triedreset = false;
bool triedDTR = false; bool triedDTR = false;
int timeout = 2500;
forever forever
{ {
{ {
...@@ -420,10 +422,19 @@ void SerialLink::run() ...@@ -420,10 +422,19 @@ void SerialLink::run()
} }
else else
{ {
if (QDateTime::currentMSecsSinceEpoch() - msecs > 10000) if (QDateTime::currentMSecsSinceEpoch() - msecs > timeout)
{ {
//It's been 10 seconds since the last data came in. Reset and try again //It's been 10 seconds since the last data came in. Reset and try again
msecs = QDateTime::currentMSecsSinceEpoch(); msecs = QDateTime::currentMSecsSinceEpoch();
if (msecs - initialmsecs > 25000)
{
//After initial 25 seconds, timeouts are increased to 30 seconds.
//This prevents temporary silences from things like calibration commands
//from screwing things up. In all reality, timeouts should be enabled/disabled
//for events like that on a case by case basis.
//TODO ^^
timeout = 30000;
}
if (!triedDTR && triedreset) if (!triedDTR && triedreset)
{ {
triedDTR = true; triedDTR = true;
......
...@@ -34,6 +34,15 @@ ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id) : ...@@ -34,6 +34,15 @@ ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id) :
//This does not seem to work. Manually request each stream type at a specified rate. //This does not seem to work. Manually request each stream type at a specified rate.
// Ask for all streams at 4 Hz // Ask for all streams at 4 Hz
//enableAllDataTransmission(4); //enableAllDataTransmission(4);
txReqTimer = new QTimer(this);
connect(txReqTimer,SIGNAL(timeout()),this,SLOT(sendTxRequests()));
QTimer::singleShot(5000,this,SLOT(sendTxRequests())); //Send an initial TX request in 5 seconds.
txReqTimer->start(300000); //Resend the TX requests every 5 minutes.
}
void ArduPilotMegaMAV::sendTxRequests()
{
enableExtendedSystemStatusTransmission(2); enableExtendedSystemStatusTransmission(2);
enablePositionTransmission(3); enablePositionTransmission(3);
enableExtra1Transmission(10); enableExtra1Transmission(10);
......
...@@ -40,6 +40,9 @@ public: ...@@ -40,6 +40,9 @@ public:
public slots: public slots:
/** @brief Receive a MAVLink message from this MAV */ /** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message); void receiveMessage(LinkInterface* link, mavlink_message_t message);
void sendTxRequests();
private:
QTimer *txReqTimer;
}; };
#endif // ARDUPILOTMAV_H #endif // ARDUPILOTMAV_H
...@@ -2523,6 +2523,15 @@ void UAS::executeCommand(MAV_CMD command) ...@@ -2523,6 +2523,15 @@ void UAS::executeCommand(MAV_CMD command)
mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd); mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
sendMessage(msg); sendMessage(msg);
} }
void UAS::executeCommandAck(int num, bool success)
{
mavlink_message_t msg;
mavlink_command_ack_t ack;
ack.command = num;
ack.result = (success ? 1 : 0);
mavlink_msg_command_ack_encode(mavlink->getSystemId(),mavlink->getComponentId(),&msg,&ack);
sendMessage(msg);
}
void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component) void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component)
{ {
......
...@@ -620,6 +620,8 @@ public slots: ...@@ -620,6 +620,8 @@ public slots:
void executeCommand(MAV_CMD command); void executeCommand(MAV_CMD command);
/** @brief Executes a command with 7 params */ /** @brief Executes a command with 7 params */
void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component); void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component);
/** @brief Executes a command ack, with success boolean **/
void executeCommandAck(int num, bool success);
/** @brief Set the current battery type and voltages */ /** @brief Set the current battery type and voltages */
void setBatterySpecs(const QString& specs); void setBatterySpecs(const QString& specs);
/** @brief Get the current battery type and specs */ /** @brief Get the current battery type and specs */
......
...@@ -227,6 +227,8 @@ public slots: ...@@ -227,6 +227,8 @@ public slots:
virtual void executeCommand(MAV_CMD command) = 0; virtual void executeCommand(MAV_CMD command) = 0;
/** @brief Executes a command **/ /** @brief Executes a command **/
virtual void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component) = 0; virtual void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component) = 0;
/** @brief Executes a command ack, with success boolean **/
virtual void executeCommandAck(int num, bool success) = 0;
/** @brief Selects the airframe */ /** @brief Selects the airframe */
virtual void setAirframe(int airframe) = 0; virtual void setAirframe(int airframe) = 0;
......
...@@ -13,6 +13,9 @@ QGCCommandButton::QGCCommandButton(QWidget *parent) : ...@@ -13,6 +13,9 @@ QGCCommandButton::QGCCommandButton(QWidget *parent) :
{ {
ui->setupUi(this); ui->setupUi(this);
responsecount = 0;
responsenum = 0;
connect(ui->commandButton, SIGNAL(clicked()), this, SLOT(sendCommand())); connect(ui->commandButton, SIGNAL(clicked()), this, SLOT(sendCommand()));
connect(ui->editFinishButton, SIGNAL(clicked()), this, SLOT(endEditMode())); connect(ui->editFinishButton, SIGNAL(clicked()), this, SLOT(endEditMode()));
connect(ui->editButtonName, SIGNAL(textChanged(QString)), this, SLOT(setCommandButtonName(QString))); connect(ui->editButtonName, SIGNAL(textChanged(QString)), this, SLOT(setCommandButtonName(QString)));
...@@ -95,6 +98,29 @@ void QGCCommandButton::sendCommand() ...@@ -95,6 +98,29 @@ void QGCCommandButton::sendCommand()
{ {
if (QGCToolWidgetItem::uas) if (QGCToolWidgetItem::uas)
{ {
if (responsenum != 0)
{
if (responsecount == 0)
{
//We're finished. Reset.
qDebug() << "Finished sequence";
QGCToolWidgetItem::uas->executeCommandAck(responsenum-responsecount,true);
responsecount = responsenum;
return;
}
if (responsecount < responsenum)
{
qDebug() << responsecount << responsenum;
QGCToolWidgetItem::uas->executeCommandAck(responsenum-responsecount,true);
responsecount--;
return;
}
else
{
qDebug() << "No sequence yet, sending command";
responsecount--;
}
}
// Check if command text is a number // Check if command text is a number
bool ok; bool ok;
int index = 0; int index = 0;
...@@ -295,6 +321,9 @@ void QGCCommandButton::readSettings(const QString& pre,const QVariantMap& settin ...@@ -295,6 +321,9 @@ void QGCCommandButton::readSettings(const QString& pre,const QVariantMap& settin
ui->editNameLabel->setText(settings.value(pre + "QGC_COMMAND_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString()); ui->editNameLabel->setText(settings.value(pre + "QGC_COMMAND_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
ui->nameLabel->setText(settings.value(pre + "QGC_COMMAND_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString()); ui->nameLabel->setText(settings.value(pre + "QGC_COMMAND_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
responsenum = settings.value(pre + "QGC_COMMAND_BUTTON_RESPONSE",0).toInt();
responsecount = responsenum;
} }
void QGCCommandButton::readSettings(const QSettings& settings) void QGCCommandButton::readSettings(const QSettings& settings)
{ {
...@@ -349,4 +378,6 @@ void QGCCommandButton::readSettings(const QSettings& settings) ...@@ -349,4 +378,6 @@ void QGCCommandButton::readSettings(const QSettings& settings)
ui->editNameLabel->setText(settings.value("QGC_COMMAND_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString()); ui->editNameLabel->setText(settings.value("QGC_COMMAND_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
ui->nameLabel->setText(settings.value("QGC_COMMAND_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString()); ui->nameLabel->setText(settings.value("QGC_COMMAND_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
responsenum = settings.value("QGC_COMMAND_BUTTON_RESPONSE",0).toInt();
responsecount = responsenum;
} }
...@@ -29,6 +29,8 @@ public slots: ...@@ -29,6 +29,8 @@ public slots:
signals: signals:
void showLabel(QString name, int num); void showLabel(QString name, int num);
private: private:
int responsenum;
int responsecount;
QString showlabelname; QString showlabelname;
Ui::QGCCommandButton *ui; Ui::QGCCommandButton *ui;
UASInterface* uas; UASInterface* uas;
......
Supports Markdown
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