Commit 2d0575fe authored by Lorenz Meier's avatar Lorenz Meier

Merged from upstream/config

parents 2708e439 31c48bba
...@@ -111,12 +111,15 @@ void QGCUASParamManager::setParameter(int compId, QString paramName, QVariant va ...@@ -111,12 +111,15 @@ void QGCUASParamManager::setParameter(int compId, QString paramName, QVariant va
paramDataModel.updatePendingParamWithValue(compId,paramName,value); paramDataModel.updatePendingParamWithValue(compId,paramName,value);
} }
void QGCUASParamManager::sendPendingParameters() void QGCUASParamManager::sendPendingParameters(bool persistAfterSend)
{ {
paramCommsMgr->sendPendingParameters(); paramCommsMgr->sendPendingParameters(persistAfterSend);
} }
void QGCUASParamManager::setPendingParam(int compId, QString& paramName, const QVariant& value)
void QGCUASParamManager::setPendingParam(int compId, const QString& paramName, const QVariant& value)
{ {
paramDataModel.updatePendingParamWithValue(compId,paramName,value); paramDataModel.updatePendingParamWithValue(compId,paramName,value);
} }
......
...@@ -84,8 +84,11 @@ public slots: ...@@ -84,8 +84,11 @@ public slots:
/** @brief Send one parameter to the MAV: changes value in transient memory of MAV */ /** @brief Send one parameter to the MAV: changes value in transient memory of MAV */
virtual void setParameter(int component, QString parameterName, QVariant value); virtual void setParameter(int component, QString parameterName, QVariant value);
/** @brief Send all pending parameters to the MAV, for storage in transient (RAM) memory */ /** @brief Send all pending parameters to the MAV, for storage in transient (RAM) memory
virtual void sendPendingParameters(); * @param persistAfterSend If true, all parameters will be written to persistent storage as well
*/
virtual void sendPendingParameters(bool persistAfterSend = false);
/** @brief Request list of parameters from MAV */ /** @brief Request list of parameters from MAV */
virtual void requestParameterList(); virtual void requestParameterList();
...@@ -93,7 +96,8 @@ public slots: ...@@ -93,7 +96,8 @@ public slots:
/** @brief Request a list of params onboard the MAV if the onboard param list we have is empty */ /** @brief Request a list of params onboard the MAV if the onboard param list we have is empty */
virtual void requestParameterListIfEmpty(); virtual void requestParameterListIfEmpty();
virtual void setPendingParam(int componentId, QString& key, const QVariant& value); /** @brief queue a pending parameter for sending to the MAV */
virtual void setPendingParam(int componentId, const QString& key, const QVariant& value);
/** @brief remove all params from the pending list */ /** @brief remove all params from the pending list */
virtual void clearAllPendingParams(); virtual void clearAllPendingParams();
......
...@@ -78,9 +78,6 @@ void UASParameterCommsMgr::requestParameterList() ...@@ -78,9 +78,6 @@ void UASParameterCommsMgr::requestParameterList()
return; return;
} }
//TODO check: no need to cause datamodel to forget params here?
// paramDataModel->forgetAllOnboardParameters();
if (!transmissionListMode) { if (!transmissionListMode) {
// Clear transmission state // Clear transmission state
receivedParamsList.clear(); receivedParamsList.clear();
...@@ -216,7 +213,7 @@ void UASParameterCommsMgr::resendReadWriteRequests() ...@@ -216,7 +213,7 @@ void UASParameterCommsMgr::resendReadWriteRequests()
} }
if ((0 == requestedWriteCount) && (0 == requestedReadCount) ) { if ((0 == requestedWriteCount) && (0 == requestedReadCount) ) {
qDebug() << __FILE__ << __LINE__ << "NO re-read or rewrite requests??"; qDebug() << __FILE__ << __LINE__ << "No pending re-read or rewrite requests";
if (!transmissionListMode) { if (!transmissionListMode) {
setRetransmissionGuardEnabled(false); setRetransmissionGuardEnabled(false);
transmissionActive = false; transmissionActive = false;
...@@ -427,6 +424,8 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para ...@@ -427,6 +424,8 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
{ {
Q_UNUSED(uas); //this object is assigned to one UAS only Q_UNUSED(uas); //this object is assigned to one UAS only
qDebug() << "compId" << compId << "receivedParameterUpdate:" << paramName;
//notify the data model that we have an updated param //notify the data model that we have an updated param
paramDataModel->handleParamUpdate(compId,paramName,value); paramDataModel->handleParamUpdate(compId,paramName,value);
...@@ -474,6 +473,10 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para ...@@ -474,6 +473,10 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
// Mark this parameter as received in write ACK list // Mark this parameter as received in write ACK list
QMap<QString, QVariant>* compMissWritePackets = missingWriteAckPackets.value(compId); QMap<QString, QVariant>* compMissWritePackets = missingWriteAckPackets.value(compId);
if (!compMissWritePackets) {
//we sometimes send a write request on compId 0 and get a response on a nonzero compId eg 50
compMissWritePackets = missingWriteAckPackets.value(0);
}
if (compMissWritePackets && compMissWritePackets->contains(paramName)) { if (compMissWritePackets && compMissWritePackets->contains(paramName)) {
justWritten = true; justWritten = true;
if (compMissWritePackets->value(paramName) != value) { if (compMissWritePackets->value(paramName) != value) {
...@@ -498,6 +501,10 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para ...@@ -498,6 +501,10 @@ void UASParameterCommsMgr::receivedParameterUpdate(int uas, int compId, int para
setParameterStatusMsg(tr("SUCCESS: Wrote %2 (#%1/%4): %3 [%5]").arg(paramId+1).arg(paramName).arg(value.toDouble()).arg(paramCount).arg(missWriteCount)); setParameterStatusMsg(tr("SUCCESS: Wrote %2 (#%1/%4): %3 [%5]").arg(paramId+1).arg(paramName).arg(value.toDouble()).arg(paramCount).arg(missWriteCount));
if (0 == missWriteCount) { if (0 == missWriteCount) {
setParameterStatusMsg(tr("SUCCESS: WROTE ALL PARAMETERS")); setParameterStatusMsg(tr("SUCCESS: WROTE ALL PARAMETERS"));
if (persistParamsAfterSend) {
writeParamsToPersistentStorage();
persistParamsAfterSend = false;
}
} }
} }
else { else {
...@@ -563,12 +570,15 @@ void UASParameterCommsMgr::writeParamsToPersistentStorage() ...@@ -563,12 +570,15 @@ void UASParameterCommsMgr::writeParamsToPersistentStorage()
{ {
if (mav) { if (mav) {
mav->writeParametersToStorage(); //TODO track timeout, retransmit etc? mav->writeParametersToStorage(); //TODO track timeout, retransmit etc?
persistParamsAfterSend = false; //done
} }
} }
void UASParameterCommsMgr::sendPendingParameters() void UASParameterCommsMgr::sendPendingParameters(bool copyToPersistent)
{ {
persistParamsAfterSend |= copyToPersistent;
// Iterate through all components, through all pending parameters and send them to UAS // Iterate through all components, through all pending parameters and send them to UAS
int parametersSent = 0; int parametersSent = 0;
QMap<int, QMap<QString, QVariant>*>* changedValues = paramDataModel->getAllPendingParams(); QMap<int, QMap<QString, QVariant>*>* changedValues = paramDataModel->getAllPendingParams();
...@@ -590,7 +600,11 @@ void UASParameterCommsMgr::sendPendingParameters() ...@@ -590,7 +600,11 @@ void UASParameterCommsMgr::sendPendingParameters()
// Change transmission status if necessary // Change transmission status if necessary
if (parametersSent == 0) { if (parametersSent == 0) {
setParameterStatusMsg(tr("No transmission: No changed values."),ParamCommsStatusLevel_Warning); setParameterStatusMsg(tr("No transmission: No changed values."),ParamCommsStatusLevel_Warning);
} else { if (persistParamsAfterSend) {
writeParamsToPersistentStorage();
}
}
else {
setParameterStatusMsg(tr("Transmitting %1 parameters.").arg(parametersSent)); setParameterStatusMsg(tr("Transmitting %1 parameters.").arg(parametersSent));
// Set timeouts // Set timeouts
if (transmissionActive) { if (transmissionActive) {
......
...@@ -64,7 +64,7 @@ signals: ...@@ -64,7 +64,7 @@ signals:
public slots: public slots:
/** @brief Iterate through all components, through all pending parameters and send them to UAS */ /** @brief Iterate through all components, through all pending parameters and send them to UAS */
virtual void sendPendingParameters(); virtual void sendPendingParameters(bool copyToPersistent = false);
/** @brief Write the current onboard parameters from transient RAM into persistent storage, e.g. EEPROM or harddisk */ /** @brief Write the current onboard parameters from transient RAM into persistent storage, e.g. EEPROM or harddisk */
virtual void writeParamsToPersistentStorage(); virtual void writeParamsToPersistentStorage();
...@@ -99,6 +99,7 @@ protected: ...@@ -99,6 +99,7 @@ protected:
bool transmissionListMode; ///< Currently requesting list bool transmissionListMode; ///< Currently requesting list
QMap<int, bool> transmissionListSizeKnown; ///< List size initialized? QMap<int, bool> transmissionListSizeKnown; ///< List size initialized?
bool transmissionActive; ///< Missing packets, working on list? bool transmissionActive; ///< Missing packets, working on list?
bool persistParamsAfterSend; ///< Copy all parameters to persistent storage after sending
quint64 transmissionTimeout; ///< Timeout quint64 transmissionTimeout; ///< Timeout
QTimer retransmissionTimer; ///< Timer handling parameter retransmission QTimer retransmissionTimer; ///< Timer handling parameter retransmission
quint64 lastTimerReset; ///< Last time the guard timer was reset, to prevent premature firing quint64 lastTimerReset; ///< Last time the guard timer was reset, to prevent premature firing
......
...@@ -45,7 +45,7 @@ int UASParameterDataModel::countOnboardParams() ...@@ -45,7 +45,7 @@ int UASParameterDataModel::countOnboardParams()
} }
bool UASParameterDataModel::updatePendingParamWithValue(int compId, QString& key, const QVariant& value) bool UASParameterDataModel::updatePendingParamWithValue(int compId, const QString& key, const QVariant& value)
{ {
bool pending = true; bool pending = true;
//ensure we have this component in our onboard and pending lists already //ensure we have this component in our onboard and pending lists already
...@@ -76,7 +76,7 @@ bool UASParameterDataModel::isParamChangePending(int compId, const QString& key) ...@@ -76,7 +76,7 @@ bool UASParameterDataModel::isParamChangePending(int compId, const QString& key)
return ((NULL != pendingParms) && pendingParms->contains(key)); return ((NULL != pendingParms) && pendingParms->contains(key));
} }
void UASParameterDataModel::setPendingParam(int compId, QString& key, const QVariant &value) void UASParameterDataModel::setPendingParam(int compId, const QString& key, const QVariant &value)
{ {
//ensure we have a placeholder map for this component //ensure we have a placeholder map for this component
addComponent(compId); addComponent(compId);
...@@ -101,7 +101,7 @@ void UASParameterDataModel::removePendingParam(int compId, const QString& key) ...@@ -101,7 +101,7 @@ void UASParameterDataModel::removePendingParam(int compId, const QString& key)
} }
} }
void UASParameterDataModel::setOnboardParam(int compId, QString& key, const QVariant& value) void UASParameterDataModel::setOnboardParam(int compId, const QString &key, const QVariant& value)
{ {
//ensure we have a placeholder map for this component //ensure we have a placeholder map for this component
addComponent(compId); addComponent(compId);
...@@ -109,7 +109,7 @@ void UASParameterDataModel::setOnboardParam(int compId, QString& key, const QVa ...@@ -109,7 +109,7 @@ void UASParameterDataModel::setOnboardParam(int compId, QString& key, const QVa
params->insert(key,value); params->insert(key,value);
} }
void UASParameterDataModel::setOnboardParamWithType(int compId, QString& key, QVariant& value) void UASParameterDataModel::setOnboardParamWithType(int compId, const QString& key, const QVariant &value)
{ {
switch ((int)value.type()) switch ((int)value.type())
...@@ -155,7 +155,7 @@ void UASParameterDataModel::addComponent(int compId) ...@@ -155,7 +155,7 @@ void UASParameterDataModel::addComponent(int compId)
} }
void UASParameterDataModel::handleParamUpdate(int compId, QString& paramName, QVariant& value) void UASParameterDataModel::handleParamUpdate(int compId, const QString &paramName, const QVariant &value)
{ {
//verify that the value requested by the user matches the set value //verify that the value requested by the user matches the set value
//if it doesn't match, leave the pending parameter in the pending list! //if it doesn't match, leave the pending parameter in the pending list!
......
...@@ -42,7 +42,7 @@ public: ...@@ -42,7 +42,7 @@ public:
virtual QList<int> getComponentForOnboardParam(const QString& parameter) const; virtual QList<int> getComponentForOnboardParam(const QString& parameter) const;
/** @brief Save the onboard parameter with a the type specified in the QVariant as fixed */ /** @brief Save the onboard parameter with a the type specified in the QVariant as fixed */
virtual void setOnboardParamWithType(int componentId, QString& key, QVariant& value); virtual void setOnboardParamWithType(int componentId, const QString &key, const QVariant& value);
/** @brief clears every parameter for every loaded component */ /** @brief clears every parameter for every loaded component */
virtual void forgetAllOnboardParams(); virtual void forgetAllOnboardParams();
...@@ -52,8 +52,8 @@ public: ...@@ -52,8 +52,8 @@ public:
/** @brief add this parameter to pending list iff it has changed from onboard value /** @brief add this parameter to pending list iff it has changed from onboard value
* @return true if the parameter is now pending * @return true if the parameter is now pending
*/ */
virtual bool updatePendingParamWithValue(int componentId, QString& key, const QVariant &value); virtual bool updatePendingParamWithValue(int componentId, const QString &key, const QVariant &value);
virtual void handleParamUpdate(int componentId, QString& key, QVariant& value); virtual void handleParamUpdate(int componentId, const QString& key, const QVariant& value);
virtual bool getOnboardParamValue(int componentId, const QString& key, QVariant& value) const; virtual bool getOnboardParamValue(int componentId, const QString& key, QVariant& value) const;
virtual bool isParamChangePending(int componentId,const QString& key); virtual bool isParamChangePending(int componentId,const QString& key);
...@@ -89,10 +89,10 @@ public: ...@@ -89,10 +89,10 @@ public:
protected: protected:
/** @brief set the confirmed value of a parameter in the onboard params list */ /** @brief set the confirmed value of a parameter in the onboard params list */
virtual void setOnboardParam(int componentId, QString& key, const QVariant& value); virtual void setOnboardParam(int componentId, const QString& key, const QVariant& value);
/** @brief Write a new pending parameter value that may be eventually sent to the UAS */ /** @brief Write a new pending parameter value that may be eventually sent to the UAS */
virtual void setPendingParam(int componentId, QString& key, const QVariant& value); virtual void setPendingParam(int componentId, const QString &key, const QVariant& value);
/** @brief remove a parameter from the pending list */ /** @brief remove a parameter from the pending list */
virtual void removePendingParam(int compId, const QString &key); virtual void removePendingParam(int compId, const QString &key);
......
...@@ -16,7 +16,7 @@ ...@@ -16,7 +16,7 @@
#include "QGCPX4VehicleConfig.h" #include "QGCPX4VehicleConfig.h"
#include "QGC.h" #include "QGC.h"
#include "QGCPendingParamWidget.h" //#include "QGCPendingParamWidget.h"
#include "QGCToolWidget.h" #include "QGCToolWidget.h"
#include "UASManager.h" #include "UASManager.h"
#include "UASParameterCommsMgr.h" #include "UASParameterCommsMgr.h"
...@@ -38,6 +38,7 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : ...@@ -38,6 +38,7 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
QWidget(parent), QWidget(parent),
mav(NULL), mav(NULL),
chanCount(0), chanCount(0),
channelWanted(-1),
rcRoll(0.0f), rcRoll(0.0f),
rcPitch(0.0f), rcPitch(0.0f),
rcYaw(0.0f), rcYaw(0.0f),
...@@ -47,7 +48,6 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : ...@@ -47,7 +48,6 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
rcAux2(0.0f), rcAux2(0.0f),
rcAux3(0.0f), rcAux3(0.0f),
dataModelChanged(true), dataModelChanged(true),
channelWanted(-1),
rc_mode(RC_MODE_NONE), rc_mode(RC_MODE_NONE),
calibrationEnabled(false), calibrationEnabled(false),
px4AirframeConfig(NULL), px4AirframeConfig(NULL),
...@@ -160,13 +160,15 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : ...@@ -160,13 +160,15 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
connect(ui->subButton, SIGNAL(clicked()), this, SLOT(identifySubModeChannel())); connect(ui->subButton, SIGNAL(clicked()), this, SLOT(identifySubModeChannel()));
connect(ui->aux1Button, SIGNAL(clicked()), this, SLOT(identifyAux1Channel())); connect(ui->aux1Button, SIGNAL(clicked()), this, SLOT(identifyAux1Channel()));
connect(ui->aux2Button, SIGNAL(clicked()), this, SLOT(identifyAux2Channel())); connect(ui->aux2Button, SIGNAL(clicked()), this, SLOT(identifyAux2Channel()));
connect(ui->persistRcValuesButt,SIGNAL(clicked()), this, SLOT(writeCalibrationRC()));
//set rc values to defaults
for (unsigned int i = 0; i < chanMax; i++) { for (unsigned int i = 0; i < chanMax; i++) {
rcValue[i] = UINT16_MAX; rcValue[i] = UINT16_MAX;
rcMapping[i] = i; rcMapping[i] = i;
channelWantedList[i] = UINT16_MAX; channelWantedList[i] = (float)UINT16_MAX;//TODO need to clean these up!
rcMin[i] = 1000; rcMin[i] = 1000.0f;
rcMax[i] = 2000; rcMax[i] = 2000.0f;
} }
updateTimer.setInterval(150); updateTimer.setInterval(150);
...@@ -211,28 +213,30 @@ void QGCPX4VehicleConfig::identifyChannelMapping(int aert_index) ...@@ -211,28 +213,30 @@ void QGCPX4VehicleConfig::identifyChannelMapping(int aert_index)
return; return;
int oldmapping = rcMapping[aert_index]; int oldmapping = rcMapping[aert_index];
channelWanted = aert_index; channelWanted = aert_index;
for (unsigned i = 0; i < sizeof(channelWantedList) / sizeof(channelWantedList[0]); i++) for (unsigned i = 0; i < chanMax; i++) {
{
if (i >= chanCount) { if (i >= chanCount) {
channelWantedList[i] = 0; channelWantedList[i] = 0;
} else { }
else {
channelWantedList[i] = rcValue[i]; channelWantedList[i] = rcValue[i];
} }
} }
msgBox.setText(tr("Identifying %1 channel").arg(channelNames[channelWanted])); msgBox.setText(tr("Identifying %1 channel").arg(channelNames[channelWanted]));
msgBox.setInformativeText(tr("Please move stick, switch or potentiometer for the %1 channel\n all the way up/down or left/right.").arg(channelNames[channelWanted])); msgBox.setInformativeText(tr("Please move stick, switch or potentiometer for the %1 channel\n all the way up/down or left/right.").arg(channelNames[channelWanted]));
msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel); msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Cancel); skipActionButton = msgBox.addButton(tr("Skip"),QMessageBox::RejectRole);
if (QMessageBox::Cancel == msgBox.exec()) msgBox.setDefaultButton(QMessageBox::Ok);
{ msgBox.exec();
skipActionButton->hide();
msgBox.removeButton(skipActionButton);
if (msgBox.clickedButton() == skipActionButton ){
channelWanted = -1; channelWanted = -1;
rcMapping[aert_index] = oldmapping; rcMapping[aert_index] = oldmapping;
return;
} }
skipActionButton = NULL;
} }
...@@ -264,36 +268,42 @@ void QGCPX4VehicleConfig::toggleCalibrationRC(bool enabled) ...@@ -264,36 +268,42 @@ void QGCPX4VehicleConfig::toggleCalibrationRC(bool enabled)
void QGCPX4VehicleConfig::setTrimPositions() void QGCPX4VehicleConfig::setTrimPositions()
{ {
int rollMap = rcMapping[0];
int pitchMap = rcMapping[1];
int yawMap = rcMapping[2];
int throttleMap = rcMapping[3];
int modeSwMap = rcMapping[4];
int aux1Map = rcMapping[5];
int aux2Map = rcMapping[6];
int aux3Map = rcMapping[7];
// Set trim to min if stick is close to min // Set trim to min if stick is close to min
if (abs(rcValue[rcMapping[3]] - rcMin[rcMapping[3]]) < 100) if (abs(rcValue[throttleMap] - rcMin[throttleMap]) < 100) {
{ rcTrim[throttleMap] = rcMin[throttleMap]; // throttle
rcTrim[rcMapping[3]] = rcMin[rcMapping[3]]; // throttle
} }
// Set trim to max if stick is close to max // Set trim to max if stick is close to max
else if (abs(rcValue[rcMapping[3]] - rcMax[rcMapping[3]]) < 100) else if (abs(rcValue[throttleMap] - rcMax[throttleMap]) < 100) {
{ rcTrim[throttleMap] = rcMax[throttleMap]; // throttle
rcTrim[rcMapping[3]] = rcMax[rcMapping[3]]; // throttle
} }
else else {
{
// Reject // Reject
QMessageBox msgBox; QMessageBox warnMsgBox;
msgBox.setText(tr("Throttle Stick Trim Position Invalid")); warnMsgBox.setText(tr("Throttle Stick Trim Position Invalid"));
msgBox.setInformativeText(tr("The throttle stick is not in the min position. Please set it to the minimum value")); warnMsgBox.setInformativeText(tr("The throttle stick is not in the min position. Please set it to the minimum value"));
msgBox.setStandardButtons(QMessageBox::Ok); warnMsgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok); warnMsgBox.setDefaultButton(QMessageBox::Ok);
(void)msgBox.exec(); (void)warnMsgBox.exec();
} }
// Set trim for roll, pitch, yaw, throttle // Set trim for roll, pitch, yaw, throttle
rcTrim[rcMapping[0]] = rcValue[rcMapping[0]]; // roll rcTrim[rollMap] = rcValue[rollMap]; // roll
rcTrim[rcMapping[1]] = rcValue[rcMapping[1]]; // pitch rcTrim[pitchMap] = rcValue[pitchMap]; // pitch
rcTrim[rcMapping[2]] = rcValue[rcMapping[2]]; // yaw rcTrim[yawMap] = rcValue[yawMap]; // yaw
rcTrim[rcMapping[4]] = ((rcMax[rcMapping[4]] - rcMin[rcMapping[4]]) / 2.0f) + rcMin[rcMapping[4]]; // mode sw rcTrim[modeSwMap] = ((rcMax[modeSwMap] - rcMin[modeSwMap]) / 2.0f) + rcMin[modeSwMap]; // mode sw
rcTrim[rcMapping[5]] = ((rcMax[rcMapping[5]] - rcMin[rcMapping[5]]) / 2.0f) + rcMin[rcMapping[5]]; // aux 1 rcTrim[aux1Map] = ((rcMax[aux1Map] - rcMin[aux1Map]) / 2.0f) + rcMin[aux1Map]; // aux 1
rcTrim[rcMapping[6]] = ((rcMax[rcMapping[6]] - rcMin[rcMapping[6]]) / 2.0f) + rcMin[rcMapping[6]]; // aux 2 rcTrim[aux2Map] = ((rcMax[aux2Map] - rcMin[aux2Map]) / 2.0f) + rcMin[aux2Map]; // aux 2
rcTrim[rcMapping[7]] = ((rcMax[rcMapping[7]] - rcMin[rcMapping[7]]) / 2.0f) + rcMin[rcMapping[7]]; // aux 3 rcTrim[aux3Map] = ((rcMax[aux3Map] - rcMin[aux3Map]) / 2.0f) + rcMin[aux3Map]; // aux 3
} }
void QGCPX4VehicleConfig::detectChannelInversion() void QGCPX4VehicleConfig::detectChannelInversion()
...@@ -305,14 +315,15 @@ void QGCPX4VehicleConfig::startCalibrationRC() ...@@ -305,14 +315,15 @@ void QGCPX4VehicleConfig::startCalibrationRC()
{ {
QMessageBox::warning(0,"Warning!","You are about to start radio calibration.\nPlease ensure all motor power is disconnected AND all props are removed from the vehicle.\nAlso ensure transmitter and receiver are powered and connected\n\nDo not move the RC sticks, then click OK to confirm"); QMessageBox::warning(0,"Warning!","You are about to start radio calibration.\nPlease ensure all motor power is disconnected AND all props are removed from the vehicle.\nAlso ensure transmitter and receiver are powered and connected\n\nDo not move the RC sticks, then click OK to confirm");
for (int i = 0; i < 5; i++) { //go ahead and try to map first 8 channels, now that user can skip channels
for (int i = 0; i < 8; i++) {
identifyChannelMapping(i); identifyChannelMapping(i);
} }
QMessageBox::information(0,"Information","Additional channels have not been mapped, but can be mapped in the channel table below."); //QMessageBox::information(0,"Information","Additional channels have not been mapped, but can be mapped in the channel table below.");
QMessageBox::information(0,"Information","Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches"); QMessageBox::information(0,"Information","Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches");
ui->rcCalibrationButton->setText(tr("Stop RC Calibration")); ui->rcCalibrationButton->setText(tr("Save RC Calibration"));
resetCalibrationRC(); resetCalibrationRC();
calibrationEnabled = true; calibrationEnabled = true;
ui->rollWidget->showMinMax(); ui->rollWidget->showMinMax();
...@@ -341,15 +352,12 @@ void QGCPX4VehicleConfig::stopCalibrationRC() ...@@ -341,15 +352,12 @@ void QGCPX4VehicleConfig::stopCalibrationRC()
ui->radio7Widget->hideMinMax(); ui->radio7Widget->hideMinMax();
ui->radio8Widget->hideMinMax(); ui->radio8Widget->hideMinMax();
for (int i=0;i<chanCount;i++) for (unsigned int i = 0; i < chanCount; i++) {
{ if (rcMin[i] > 1350) {
if (rcMin[i] > 1350)
{
rcMin[i] = 1000; rcMin[i] = 1000;
} }
if (rcMax[i] < 1650) if (rcMax[i] < 1650) {
{
rcMax[i] = 2000; rcMax[i] = 2000;
} }
} }
...@@ -362,11 +370,18 @@ void QGCPX4VehicleConfig::stopCalibrationRC() ...@@ -362,11 +370,18 @@ void QGCPX4VehicleConfig::stopCalibrationRC()
statusstr += "Normal values are around 1100 to 1900, with disconnected channels reading 1000, 1500, 2000\n\n"; statusstr += "Normal values are around 1100 to 1900, with disconnected channels reading 1000, 1500, 2000\n\n";
statusstr += "Channel\tMin\tCenter\tMax\n"; statusstr += "Channel\tMin\tCenter\tMax\n";
statusstr += "--------------------\n"; statusstr += "--------------------\n";
for (int i=0;i<chanCount;i++) for (unsigned int i=0; i < chanCount; i++) {
{
statusstr += QString::number(i) +"\t"+ QString::number(rcMin[i]) +"\t"+ QString::number(rcValue[i]) +"\t"+ QString::number(rcMax[i]) +"\n"; statusstr += QString::number(i) +"\t"+ QString::number(rcMin[i]) +"\t"+ QString::number(rcValue[i]) +"\t"+ QString::number(rcMax[i]) +"\n";
} }
QMessageBox::information(0,"Status",statusstr);
msgBox.setText(tr("Confirm Calibration"));
msgBox.setInformativeText(statusstr);
msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel);//allow user to cancel upload after reviewing values
int msgBoxResult = msgBox.exec();
if (QMessageBox::Cancel == msgBoxResult) {
return;//don't commit these values
}
QMessageBox::information(0,"Uploading the RC Calibration","The configuration will now be uploaded and permanently stored."); QMessageBox::information(0,"Uploading the RC Calibration","The configuration will now be uploaded and permanently stored.");
writeCalibrationRC(); writeCalibrationRC();
...@@ -1005,7 +1020,6 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active) ...@@ -1005,7 +1020,6 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
chanCount = 0; chanCount = 0;
//TODO get parameter changes via Param Mgr instead
// Connect new system // Connect new system
connect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this, connect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
SLOT(remoteControlChannelRawChanged(int,float))); SLOT(remoteControlChannelRawChanged(int,float)));
...@@ -1056,8 +1070,7 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active) ...@@ -1056,8 +1070,7 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
void QGCPX4VehicleConfig::resetCalibrationRC() void QGCPX4VehicleConfig::resetCalibrationRC()
{ {
for (unsigned int i = 0; i < chanMax; ++i) for (unsigned int i = 0; i < chanMax; ++i) {
{
rcMin[i] = 1500; rcMin[i] = 1500;
rcMax[i] = 1500; rcMax[i] = 1500;
} }
...@@ -1070,6 +1083,8 @@ void QGCPX4VehicleConfig::writeCalibrationRC() ...@@ -1070,6 +1083,8 @@ void QGCPX4VehicleConfig::writeCalibrationRC()
{ {
if (!mav) return; if (!mav) return;
updateStatus(tr("Sending RC configuration and storing to persistent memory."));
QString minTpl("RC%1_MIN"); QString minTpl("RC%1_MIN");
QString maxTpl("RC%1_MAX"); QString maxTpl("RC%1_MAX");
QString trimTpl("RC%1_TRIM"); QString trimTpl("RC%1_TRIM");
...@@ -1078,39 +1093,27 @@ void QGCPX4VehicleConfig::writeCalibrationRC() ...@@ -1078,39 +1093,27 @@ void QGCPX4VehicleConfig::writeCalibrationRC()
// Do not write the RC type, as these values depend on this // Do not write the RC type, as these values depend on this
// active onboard parameter // active onboard parameter
//TODO consolidate RC param sending in the UAS comms mgr for (unsigned int i = 0; i < chanCount; ++i) {
for (unsigned int i = 0; i < chanCount; ++i)
{
//qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i]; //qDebug() << "SENDING" << minTpl.arg(i+1) << rcMin[i];
mav->setParameter(0, minTpl.arg(i+1), rcMin[i]); paramMgr->setPendingParam(0, minTpl.arg(i+1), rcMin[i]);
QGC::SLEEP::usleep(50000); paramMgr->setPendingParam(0, trimTpl.arg(i+1), rcTrim[i]);
mav->setParameter(0, trimTpl.arg(i+1), rcTrim[i]); paramMgr->setPendingParam(0, maxTpl.arg(i+1), rcMax[i]);
QGC::SLEEP::usleep(50000); paramMgr->setPendingParam(0, revTpl.arg(i+1), (rcRev[i]) ? -1.0f : 1.0f);
mav->setParameter(0, maxTpl.arg(i+1), rcMax[i]);
QGC::SLEEP::usleep(50000);
mav->setParameter(0, revTpl.arg(i+1), (rcRev[i]) ? -1.0f : 1.0f);
QGC::SLEEP::usleep(50000);
} }
// Write mappings // Write mappings
mav->setParameter(0, "RC_MAP_ROLL", (int32_t)(rcMapping[0]+1)); paramMgr->setPendingParam(0, "RC_MAP_ROLL", (int32_t)(rcMapping[0]+1));
QGC::SLEEP::usleep(50000); paramMgr->setPendingParam(0, "RC_MAP_PITCH", (int32_t)(rcMapping[1]+1));
mav->setParameter(0, "RC_MAP_PITCH", (int32_t)(rcMapping[1]+1)); paramMgr->setPendingParam(0, "RC_MAP_YAW", (int32_t)(rcMapping[2]+1));
QGC::SLEEP::usleep(50000); paramMgr->setPendingParam(0, "RC_MAP_THROTTLE", (int32_t)(rcMapping[3]+1));
mav->setParameter(0, "RC_MAP_YAW", (int32_t)(rcMapping[2]+1)); paramMgr->setPendingParam(0, "RC_MAP_MODE_SW", (int32_t)(rcMapping[4]+1));
QGC::SLEEP::usleep(50000); paramMgr->setPendingParam(0, "RC_MAP_AUX1", (int32_t)(rcMapping[5]+1));
mav->setParameter(0, "RC_MAP_THROTTLE", (int32_t)(rcMapping[3]+1)); paramMgr->setPendingParam(0, "RC_MAP_AUX2", (int32_t)(rcMapping[6]+1));
QGC::SLEEP::usleep(50000); paramMgr->setPendingParam(0, "RC_MAP_AUX3", (int32_t)(rcMapping[7]+1));
mav->setParameter(0, "RC_MAP_MODE_SW", (int32_t)(rcMapping[4]+1));
QGC::SLEEP::usleep(50000); //let the param mgr manage sending all the pending RC_foo updates and persisting after
mav->setParameter(0, "RC_MAP_AUX1", (int32_t)(rcMapping[5]+1)); paramMgr->sendPendingParameters(true);
QGC::SLEEP::usleep(50000);
mav->setParameter(0, "RC_MAP_AUX2", (int32_t)(rcMapping[6]+1));
QGC::SLEEP::usleep(50000);
mav->setParameter(0, "RC_MAP_AUX3", (int32_t)(rcMapping[7]+1));
QGC::SLEEP::usleep(50000);
mav->getParamManager()->copyVolatileParamsToPersistent();
} }
void QGCPX4VehicleConfig::requestCalibrationRC() void QGCPX4VehicleConfig::requestCalibrationRC()
...@@ -1122,13 +1125,12 @@ void QGCPX4VehicleConfig::writeParameters() ...@@ -1122,13 +1125,12 @@ void QGCPX4VehicleConfig::writeParameters()
{ {
updateStatus(tr("Writing all onboard parameters.")); updateStatus(tr("Writing all onboard parameters."));
writeCalibrationRC(); writeCalibrationRC();
mav->writeParametersToStorage();
} }
void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val) void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float fval)
{ {
// Check if index and values are sane // Check if index and values are sane
if (chan < 0 || static_cast<unsigned int>(chan) >= chanMax || val < 500 || val > 2500) if (chan < 0 || static_cast<unsigned int>(chan) >= chanMax || fval < 500.0f || fval > 2500.0f)
return; return;
if (chan + 1 > (int)chanCount) { if (chan + 1 > (int)chanCount) {
...@@ -1136,27 +1138,35 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val) ...@@ -1136,27 +1138,35 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val)
} }
// Raw value // Raw value
rcValue[chan] = val; int ival = (int)fval;
int delta = abs(ival - rcValue[chan]);
if (delta < 3) {
//ignore tiny jitter values
return;
}
else {
qDebug() << "chan" << chan << " delta:" << delta;
rcValue[chan] = ival;
}
// Update calibration data // Update calibration data
if (calibrationEnabled) { if (calibrationEnabled) {
if (val < rcMin[chan]) { if (fval < rcMin[chan]) {
rcMin[chan] = val; rcMin[chan] = fval;
} }
if (val > rcMax[chan]) { if (fval > rcMax[chan]) {
rcMax[chan] = val; rcMax[chan] = fval;
} }
} }
if (channelWanted >= 0) { if (channelWanted >= 0) {
// If the first channel moved considerably, pick it // If the first channel moved considerably, pick it
if (fabsf(channelWantedList[chan] - val) > 300) if (fabsf(channelWantedList[chan] - fval) > 300.0f) {
{
rcMapping[channelWanted] = chan; rcMapping[channelWanted] = chan;
updateInvertedCheckboxes(chan); updateInvertedCheckboxes(chan);
int chanFound = channelWanted; int chanFound = channelWanted;
channelWanted = -1; channelWanted = -1;
// Confirm found channel // Confirm found channel
...@@ -1169,12 +1179,9 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val) ...@@ -1169,12 +1179,9 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val)
} }
// Find correct mapped channel // Find correct mapped channel
for (int i = 0; i < chanCount; i++) for (unsigned int i = 0; i < chanCount; i++) {
{ if (chan == rcMapping[i]) {
if (chan == rcMapping[i]) rcMappedValue[i] = (rcRev[chan]) ? rcMax[chan] - (fval - rcMin[chan]) : fval;
{
rcMappedValue[i] = (rcRev[chan]) ? rcMax[chan] - (val - rcMin[chan]) : val;
// Copy min / max // Copy min / max
rcMappedMin[i] = rcMin[chan]; rcMappedMin[i] = rcMin[chan];
...@@ -1184,12 +1191,12 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val) ...@@ -1184,12 +1191,12 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val)
// Normalized value // Normalized value
float normalized; float normalized;
float chanTrim = rcTrim[chan];
if (val >= rcTrim[chan]) { if (fval >= rcTrim[chan]) {
normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]); normalized = (fval - chanTrim)/(rcMax[chan] - chanTrim);
} }
else { else {
normalized = -(rcTrim[chan] - val)/(rcTrim[chan] - rcMin[chan]); normalized = -(chanTrim - fval)/(chanTrim - rcMin[chan]);
} }
// Bound // Bound
...@@ -1209,7 +1216,8 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val) ...@@ -1209,7 +1216,8 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val)
else if (chan == rcMapping[3]) { else if (chan == rcMapping[3]) {
if (rcRev[chan]) { if (rcRev[chan]) {
rcThrottle = 1.0f + normalized; rcThrottle = 1.0f + normalized;
} else { }
else {
rcThrottle = normalized; rcThrottle = normalized;
} }
...@@ -1230,7 +1238,7 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val) ...@@ -1230,7 +1238,7 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float val)
dataModelChanged = true; dataModelChanged = true;
//qDebug() << "RC CHAN:" << chan << "PPM:" << val << "NORMALIZED:" << normalized; qDebug() << "RC CHAN:" << chan << "PPM:" << fval << "NORMALIZED:" << normalized;
} }
void QGCPX4VehicleConfig::updateInvertedCheckboxes(int index) void QGCPX4VehicleConfig::updateInvertedCheckboxes(int index)
...@@ -1505,10 +1513,8 @@ void QGCPX4VehicleConfig::setRCType(int type) ...@@ -1505,10 +1513,8 @@ void QGCPX4VehicleConfig::setRCType(int type)
void QGCPX4VehicleConfig::checktimeOuts() void QGCPX4VehicleConfig::checktimeOuts()
{ {
if (rcTypeUpdateRequested > 0) if (rcTypeUpdateRequested > 0) {
{ if (QGC::groundTimeMilliseconds() - rcTypeUpdateRequested > rcTypeTimeout) {
if (QGC::groundTimeMilliseconds() - rcTypeUpdateRequested > rcTypeTimeout)
{
updateError(tr("Setting remote control timed out - is the system connected?")); updateError(tr("Setting remote control timed out - is the system connected?"));
} }
} }
...@@ -1528,42 +1534,49 @@ void QGCPX4VehicleConfig::updateRcWidgetValues() ...@@ -1528,42 +1534,49 @@ void QGCPX4VehicleConfig::updateRcWidgetValues()
ui->radio8Widget->setValueAndRange(rcMappedValue[7],rcMin[7],rcMax[7]); ui->radio8Widget->setValueAndRange(rcMappedValue[7],rcMin[7],rcMax[7]);
} }
void QGCPX4VehicleConfig::updateView() void QGCPX4VehicleConfig::updateRcChanLabels()
{ {
if (dataModelChanged) { ui->rollChanLabel->setText(labelForRcValue(rcRoll));
dataModelChanged = false; ui->pitchChanLabel->setText(labelForRcValue(rcPitch));
ui->yawChanLabel->setText(labelForRcValue(rcYaw));
updateRcWidgetValues(); ui->throttleChanLabel->setText(labelForRcValue(rcThrottle));
//update the channel labels QString blankLabel = tr("---");
ui->rollChanLabel->setText(QString("%1").arg(rcRoll, 5, 'f', 2, QChar(' '))); if (rcValue[rcMapping[4] != UINT16_MAX]) {
ui->pitchChanLabel->setText(QString("%1").arg(rcPitch, 5, 'f', 2, QChar(' '))); ui->modeChanLabel->setText(labelForRcValue(rcMode));
ui->yawChanLabel->setText(QString("%1").arg(rcYaw, 5, 'f', 2, QChar(' '))); }
ui->throttleChanLabel->setText(QString("%1").arg(rcThrottle, 5, 'f', 2, QChar(' '))); else {
ui->modeChanLabel->setText(blankLabel);
}
if (rcValue[rcMapping[4] != UINT16_MAX]) { if (rcValue[rcMapping[5]] != UINT16_MAX) {
ui->modeChanLabel->setText(QString("%1").arg(rcMode, 5, 'f', 2, QChar(' '))); ui->aux1ChanLabel->setText(labelForRcValue(rcAux1));
} else { }
ui->modeChanLabel->setText(tr("---")); else {
} ui->aux1ChanLabel->setText(blankLabel);
}
if (rcValue[rcMapping[5]] != UINT16_MAX) { if (rcValue[rcMapping[6]] != UINT16_MAX) {
ui->aux1ChanLabel->setText(QString("%1").arg(rcAux1, 5, 'f', 2, QChar(' '))); ui->aux2ChanLabel->setText(labelForRcValue(rcAux2));
} else { }
ui->aux1ChanLabel->setText(tr("---")); else {
} ui->aux2ChanLabel->setText(blankLabel);
}
if (rcValue[rcMapping[6]] != UINT16_MAX) { if (rcValue[rcMapping[7]] != UINT16_MAX) {
ui->aux2ChanLabel->setText(QString("%1").arg(rcAux2, 5, 'f', 2, QChar(' '))); ui->aux3ChanLabel->setText(labelForRcValue(rcAux3));
} else { }
ui->aux2ChanLabel->setText(tr("---")); else {
} ui->aux3ChanLabel->setText(blankLabel);
}
}
if (rcValue[rcMapping[7]] != UINT16_MAX) { void QGCPX4VehicleConfig::updateView()
ui->aux3ChanLabel->setText(QString("%1").arg(rcAux3, 5, 'f', 2, QChar(' '))); {
} else { if (dataModelChanged) {
ui->aux3ChanLabel->setText(tr("---")); dataModelChanged = false;
}
updateRcWidgetValues();
updateRcChanLabels();
} }
} }
...@@ -66,7 +66,7 @@ public slots: ...@@ -66,7 +66,7 @@ public slots:
void setRCModeIndex(int newRcMode); void setRCModeIndex(int newRcMode);
/** Render the data updated */ /** Render the data updated */
void updateView(); void updateView();
void updateRcWidgetValues();
void handleRcParameterChange(QString parameterName, QVariant value); void handleRcParameterChange(QString parameterName, QVariant value);
...@@ -205,6 +205,14 @@ protected slots: ...@@ -205,6 +205,14 @@ protected slots:
void checktimeOuts(); void checktimeOuts();
/** Update checkbox status */ /** Update checkbox status */
void updateInvertedCheckboxes(int index); void updateInvertedCheckboxes(int index);
/** Update the displayed values */
void updateRcWidgetValues();
/** update the channel labels */
void updateRcChanLabels();
QString labelForRcValue(float val) {
return QString("%1").arg(val, 5, 'f', 2, QChar(' '));
}
protected: protected:
bool doneLoadingConfig; bool doneLoadingConfig;
...@@ -254,6 +262,7 @@ protected: ...@@ -254,6 +262,7 @@ protected:
QGCPX4AirframeConfig* px4AirframeConfig; QGCPX4AirframeConfig* px4AirframeConfig;
DialogBare* firmwareDialog; DialogBare* firmwareDialog;
QMessageBox msgBox; QMessageBox msgBox;
QPushButton* skipActionButton;
private: private:
Ui::QGCPX4VehicleConfig *ui; Ui::QGCPX4VehicleConfig *ui;
......
...@@ -154,7 +154,7 @@ Config</string> ...@@ -154,7 +154,7 @@ Config</string>
<item> <item>
<widget class="QStackedWidget" name="stackedWidget"> <widget class="QStackedWidget" name="stackedWidget">
<property name="currentIndex"> <property name="currentIndex">
<number>1</number> <number>5</number>
</property> </property>
<widget class="QWidget" name="firmwareTab"> <widget class="QWidget" name="firmwareTab">
<layout class="QVBoxLayout" name="firmwareLayout"> <layout class="QVBoxLayout" name="firmwareLayout">
...@@ -746,6 +746,13 @@ Config</string> ...@@ -746,6 +746,13 @@ Config</string>
</item> </item>
</layout> </layout>
</item> </item>
<item>
<widget class="QPushButton" name="persistRcValuesButt">
<property name="text">
<string>Persist RC Mapping and Calibration</string>
</property>
</widget>
</item>
</layout> </layout>
</widget> </widget>
</item> </item>
...@@ -874,8 +881,8 @@ Config</string> ...@@ -874,8 +881,8 @@ Config</string>
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>98</width> <width>16</width>
<height>28</height> <height>16</height>
</rect> </rect>
</property> </property>
<layout class="QHBoxLayout" name="horizontalLayout_4"> <layout class="QHBoxLayout" name="horizontalLayout_4">
...@@ -911,8 +918,8 @@ Config</string> ...@@ -911,8 +918,8 @@ Config</string>
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>98</width> <width>16</width>
<height>28</height> <height>16</height>
</rect> </rect>
</property> </property>
<layout class="QHBoxLayout" name="horizontalLayout_5"> <layout class="QHBoxLayout" name="horizontalLayout_5">
...@@ -1003,8 +1010,8 @@ Config</string> ...@@ -1003,8 +1010,8 @@ Config</string>
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>98</width> <width>597</width>
<height>28</height> <height>569</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_7"> <layout class="QVBoxLayout" name="verticalLayout_7">
......
...@@ -1020,12 +1020,10 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val) ...@@ -1020,12 +1020,10 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val)
// Normalized value // Normalized value
float normalized; float normalized;
if (val >= rcTrim[chan]) if (val >= rcTrim[chan]) {
{
normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]); normalized = (val - rcTrim[chan])/(rcMax[chan] - rcTrim[chan]);
} }
else else {
{
normalized = -(rcTrim[chan] - val)/(rcTrim[chan] - rcMin[chan]); normalized = -(rcTrim[chan] - val)/(rcTrim[chan] - rcMin[chan]);
} }
...@@ -1034,22 +1032,18 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val) ...@@ -1034,22 +1032,18 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val)
// Invert // Invert
normalized = (rcRev[chan]) ? -1.0f*normalized : normalized; normalized = (rcRev[chan]) ? -1.0f*normalized : normalized;
if (chan == rcMapping[0]) if (chan == rcMapping[0]) {
{
// ROLL // ROLL
rcRoll = normalized; rcRoll = normalized;
} }
if (chan == rcMapping[1]) if (chan == rcMapping[1]) {
{
// PITCH // PITCH
rcPitch = normalized; rcPitch = normalized;
} }
if (chan == rcMapping[2]) if (chan == rcMapping[2]) {
{
rcYaw = normalized; rcYaw = normalized;
} }
if (chan == rcMapping[3]) if (chan == rcMapping[3]) {
{
// THROTTLE // THROTTLE
if (rcRev[chan]) { if (rcRev[chan]) {
rcThrottle = 1.0f + normalized; rcThrottle = 1.0f + normalized;
...@@ -1059,23 +1053,19 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val) ...@@ -1059,23 +1053,19 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val)
rcThrottle = qBound(0.0f, rcThrottle, 1.0f); rcThrottle = qBound(0.0f, rcThrottle, 1.0f);
} }
if (chan == rcMapping[4]) if (chan == rcMapping[4]) {
{
// MODE SWITCH // MODE SWITCH
rcMode = normalized; rcMode = normalized;
} }
if (chan == rcMapping[5]) if (chan == rcMapping[5]) {
{
// AUX1 // AUX1
rcAux1 = normalized; rcAux1 = normalized;
} }
if (chan == rcMapping[6]) if (chan == rcMapping[6]) {
{
// AUX2 // AUX2
rcAux2 = normalized; rcAux2 = normalized;
} }
if (chan == rcMapping[7]) if (chan == rcMapping[7]) {
{
// AUX3 // AUX3
rcAux3 = normalized; rcAux3 = normalized;
} }
......
...@@ -161,11 +161,8 @@ void QGCPX4AirframeConfig::applyAndReboot() ...@@ -161,11 +161,8 @@ void QGCPX4AirframeConfig::applyAndReboot()
//mav->getParamManager()->setParameter(components.first(), "SYS_AUTOSTART", (qint32)selectedId); //mav->getParamManager()->setParameter(components.first(), "SYS_AUTOSTART", (qint32)selectedId);
// Send pending params // Send pending params
mav->getParamManager()->sendPendingParameters(); mav->getParamManager()->sendPendingParameters(true);
QGC::SLEEP::msleep(300);
// Store parameters
mav->getParamManager()->copyVolatileParamsToPersistent();
QGC::SLEEP::msleep(500);
// Reboot // Reboot
mav->executeCommand(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0); mav->executeCommand(MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0);
} }
......
#include "QGCMessageView.h" #include "QGCMessageView.h"
#include "ui_QGCMessageView.h"
#include "UASManager.h"
#include "QGCUnconnectedInfoWidget.h"
#include <QMenu> #include <QMenu>
#include <QScrollBar> #include <QScrollBar>
#include "GAudioOutput.h"
#include "QGCUnconnectedInfoWidget.h"
#include "UASManager.h"
#include "ui_QGCMessageView.h"
QGCMessageView::QGCMessageView(QWidget *parent) : QGCMessageView::QGCMessageView(QWidget *parent) :
QWidget(parent), QWidget(parent),
activeUAS(NULL), activeUAS(NULL),
...@@ -53,7 +57,7 @@ void QGCMessageView::setActiveUAS(UASInterface* uas) ...@@ -53,7 +57,7 @@ void QGCMessageView::setActiveUAS(UASInterface* uas)
activeUAS = uas; activeUAS = uas;
} }
void QGCMessageView::handleTextMessage(int uasid, int componentid, int severity, QString text) void QGCMessageView::handleTextMessage(int uasid, int compId, int severity, QString text)
{ {
// XXX color messages according to severity // XXX color messages according to severity
...@@ -64,7 +68,17 @@ void QGCMessageView::handleTextMessage(int uasid, int componentid, int severity, ...@@ -64,7 +68,17 @@ void QGCMessageView::handleTextMessage(int uasid, int componentid, int severity,
QScrollBar *scroller = msgWidget->verticalScrollBar(); QScrollBar *scroller = msgWidget->verticalScrollBar();
UASInterface *uas = UASManager::instance()->getUASForId(uasid); UASInterface *uas = UASManager::instance()->getUASForId(uasid);
msgWidget->appendHtml(QString("<font color=\"%1\">[%2:%3] %4</font>\n").arg(uas->getColor().name()).arg(uas->getUASName()).arg(componentid).arg(text)); QString uasName(uas->getUASName());
QString colorName(uas->getColor().name());
//change styling based on severity
if (160 == severity ) { //TODO where is the constant for "critical" severity?
GAudioOutput::instance()->say(text.toLower());
msgWidget->appendHtml(QString("<p style=\"color:#DC143C;background-color:#FFFACD;font-size:large;font-weight:bold\">[%1:%2] %3</p>").arg(uasName).arg(compId).arg(text));
}
else {
msgWidget->appendHtml(QString("<p style=\"color:%1;font-size:smaller\">[%2:%3] %4</p>").arg(colorName).arg(uasName).arg(compId).arg(text));
}
// Ensure text area scrolls correctly // Ensure text area scrolls correctly
scroller->setValue(scroller->maximum()); scroller->setValue(scroller->maximum());
msgWidget->setUpdatesEnabled(true); msgWidget->setUpdatesEnabled(true);
......
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