mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Merge remote-tracking branch 'op-public/next' into revo-next
Conflicts: flight/Modules/Telemetry/telemetry.c ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro
This commit is contained in:
commit
5aa3777078
@ -163,6 +163,16 @@ C: Eric Price (Corvus Corax)
|
||||
D: December 2011
|
||||
V: http://www.youtube.com/watch?v=nWNWuUiUTNg
|
||||
|
||||
M: First CopterControl over 5km FixedWing navigation flight
|
||||
C: Kavin Gustafson (k_g)
|
||||
D: October 2012
|
||||
V: http://www.youtube.com/watch?v=MGO68TqIwKk
|
||||
|
||||
M: First CopterControl over 10km FixedWing navigation flight
|
||||
C:
|
||||
D:
|
||||
V:
|
||||
|
||||
M: First successful flight using the GCS only and no RC TX
|
||||
C:
|
||||
D:
|
||||
@ -211,8 +221,8 @@ D:
|
||||
V:
|
||||
|
||||
M: First Revo 5km Navigated flight on a FixedWing
|
||||
C:
|
||||
D:
|
||||
C: Eric Price (Corvus Corax)
|
||||
D: March 2012
|
||||
V:
|
||||
|
||||
M: First Revo 1km Navigated flight on a Heli
|
||||
@ -230,11 +240,6 @@ C:
|
||||
D:
|
||||
V:
|
||||
|
||||
M: First Auto landing on a fixed Wing using CC
|
||||
C:
|
||||
D:
|
||||
V:
|
||||
|
||||
M: First Auto landing on a fixed Wing using Revo
|
||||
C:
|
||||
D:
|
||||
|
@ -213,7 +213,6 @@ SRC += $(OPUAVSYNTHDIR)/camerastabsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/cameradesired.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gpsposition.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gpsvelocity.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gpssettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/hwsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c
|
||||
SRC += $(OPUAVSYNTHDIR)/receiveractivity.c
|
||||
|
@ -38,7 +38,7 @@
|
||||
#include "gpstime.h"
|
||||
#include "gpssatellites.h"
|
||||
#include "gpsvelocity.h"
|
||||
#include "gpssettings.h"
|
||||
#include "systemsettings.h"
|
||||
#include "WorldMagModel.h"
|
||||
#include "CoordinateConversions.h"
|
||||
#include "hwsettings.h"
|
||||
@ -165,13 +165,13 @@ int32_t GPSInitialize(void)
|
||||
#endif
|
||||
|
||||
if (gpsPort && gpsEnabled) {
|
||||
GPSSettingsInitialize();
|
||||
GPSSettingsDataProtocolGet(&gpsProtocol);
|
||||
SystemSettingsInitialize();
|
||||
SystemSettingsGPSDataProtocolGet(&gpsProtocol);
|
||||
switch (gpsProtocol) {
|
||||
case GPSSETTINGS_DATAPROTOCOL_NMEA:
|
||||
case SYSTEMSETTINGS_GPSDATAPROTOCOL_NMEA:
|
||||
gps_rx_buffer = pvPortMalloc(NMEA_MAX_PACKET_LENGTH);
|
||||
break;
|
||||
case GPSSETTINGS_DATAPROTOCOL_UBX:
|
||||
case SYSTEMSETTINGS_GPSDATAPROTOCOL_UBX:
|
||||
gps_rx_buffer = pvPortMalloc(sizeof(struct UBXPacket));
|
||||
break;
|
||||
default:
|
||||
@ -200,7 +200,7 @@ static void gpsTask(void *parameters)
|
||||
GPSPositionData gpsposition;
|
||||
uint8_t gpsProtocol;
|
||||
|
||||
GPSSettingsDataProtocolGet(&gpsProtocol);
|
||||
SystemSettingsGPSDataProtocolGet(&gpsProtocol);
|
||||
|
||||
timeOfLastUpdateMs = timeNowMs;
|
||||
timeOfLastCommandMs = timeNowMs;
|
||||
@ -217,12 +217,12 @@ static void gpsTask(void *parameters)
|
||||
int res;
|
||||
switch (gpsProtocol) {
|
||||
#if defined(PIOS_INCLUDE_GPS_NMEA_PARSER)
|
||||
case GPSSETTINGS_DATAPROTOCOL_NMEA:
|
||||
case SYSTEMSETTINGS_GPSDATAPROTOCOL_NMEA:
|
||||
res = parse_nmea_stream (c,gps_rx_buffer, &gpsposition, &gpsRxStats);
|
||||
break;
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_GPS_UBX_PARSER)
|
||||
case GPSSETTINGS_DATAPROTOCOL_UBX:
|
||||
case SYSTEMSETTINGS_GPSDATAPROTOCOL_UBX:
|
||||
res = parse_ubx_stream (c,gps_rx_buffer, &gpsposition, &gpsRxStats);
|
||||
break;
|
||||
#endif
|
||||
|
@ -252,12 +252,11 @@ static void processObjEvent(UAVObjEvent * ev)
|
||||
} else if (ev->obj == GCSTelemetryStatsHandle()) {
|
||||
gcsTelemetryStatsUpdated();
|
||||
} else {
|
||||
// Only process event if connected to GCS or if object FlightTelemetryStats is updated
|
||||
FlightTelemetryStatsGet(&flightStats);
|
||||
// Get object metadata
|
||||
UAVObjGetMetadata(ev->obj, &metadata);
|
||||
updateMode = UAVObjGetTelemetryUpdateMode(&metadata);
|
||||
if (flightStats.Status == FLIGHTTELEMETRYSTATS_STATUS_CONNECTED || ev->obj == FlightTelemetryStatsHandle()) {
|
||||
|
||||
// Act on event
|
||||
retries = 0;
|
||||
success = -1;
|
||||
@ -293,7 +292,7 @@ static void processObjEvent(UAVObjEvent * ev)
|
||||
if (UAVObjIsMetaobject(ev->obj)) {
|
||||
updateObject(UAVObjGetLinkedObj(ev->obj), EV_NONE); // linked object will be the actual object the metadata are for
|
||||
}
|
||||
}
|
||||
|
||||
if((updateMode == UPDATEMODE_THROTTLED) && !UAVObjIsMetaobject(ev->obj)) {
|
||||
// If this is UPDATEMODE_THROTTLED, the event mask changes on every event.
|
||||
updateObject(ev->obj, ev->event);
|
||||
|
@ -251,7 +251,7 @@ int32_t PIOS_Flash_Jedec_ReadStatus()
|
||||
*/
|
||||
int32_t PIOS_Flash_Jedec_ReadID()
|
||||
{
|
||||
uint8_t out[] = {JEDEC_DEVICE_ID};
|
||||
uint8_t out[] = {JEDEC_DEVICE_ID, 0, 0, 0};
|
||||
uint8_t in[4];
|
||||
if (PIOS_Flash_Jedec_ClaimBus() < 0)
|
||||
return -1;
|
||||
|
@ -50,7 +50,6 @@ UAVOBJSRCFILENAMES += gcstelemetrystats
|
||||
UAVOBJSRCFILENAMES += gcsreceiver
|
||||
UAVOBJSRCFILENAMES += gpsposition
|
||||
UAVOBJSRCFILENAMES += gpssatellites
|
||||
UAVOBJSRCFILENAMES += gpssettings
|
||||
UAVOBJSRCFILENAMES += gpstime
|
||||
UAVOBJSRCFILENAMES += gpsvelocity
|
||||
UAVOBJSRCFILENAMES += fixedwingpathfollowersettings
|
||||
|
@ -48,7 +48,6 @@ UAVOBJSRCFILENAMES += gcstelemetrystats
|
||||
UAVOBJSRCFILENAMES += gpsposition
|
||||
UAVOBJSRCFILENAMES += gpssatellites
|
||||
UAVOBJSRCFILENAMES += gpstime
|
||||
UAVOBJSRCFILENAMES += gpssettings
|
||||
UAVOBJSRCFILENAMES += gpsvelocity
|
||||
UAVOBJSRCFILENAMES += vtolpathfollowersettings
|
||||
UAVOBJSRCFILENAMES += fixedwingpathfollowersettings
|
||||
|
@ -34,7 +34,7 @@ namespace mapcontrol
|
||||
pic=pic.scaled(30,30,Qt::IgnoreAspectRatio);
|
||||
this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true);
|
||||
this->setFlag(QGraphicsItem::ItemIsMovable,false);
|
||||
this->setFlag(QGraphicsItem::ItemIsSelectable,false);
|
||||
this->setFlag(QGraphicsItem::ItemIsSelectable,true);
|
||||
localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition());
|
||||
this->setPos(localposition.X(),localposition.Y());
|
||||
this->setZValue(4);
|
||||
@ -142,5 +142,14 @@ namespace mapcontrol
|
||||
}
|
||||
QGraphicsItem::mouseMoveEvent(event);
|
||||
}
|
||||
|
||||
//Set clickable area as smaller than the bounding rect.
|
||||
QPainterPath HomeItem::shape() const
|
||||
{
|
||||
QPainterPath path;
|
||||
path.addEllipse(QRectF(-12, -25, 24, 50));
|
||||
return path;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
@ -76,6 +76,7 @@ namespace mapcontrol
|
||||
void mousePressEvent ( QGraphicsSceneMouseEvent * event );
|
||||
void mouseReleaseEvent ( QGraphicsSceneMouseEvent * event );
|
||||
void mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event);
|
||||
QPainterPath shape() const;
|
||||
public slots:
|
||||
void RefreshPos();
|
||||
void setOpacitySlot(qreal opacity);
|
||||
|
@ -49,7 +49,15 @@
|
||||
#define STICK_MIN_MOVE -8
|
||||
#define STICK_MAX_MOVE 8
|
||||
|
||||
ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent),wizardStep(wizardNone),transmitterType(heli),loop(NULL),skipflag(false)
|
||||
ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
ConfigTaskWidget(parent),
|
||||
wizardStep(wizardNone),
|
||||
// not currently stored in the settings UAVO
|
||||
transmitterMode(mode2),
|
||||
transmitterType(acro),
|
||||
//
|
||||
loop(NULL),
|
||||
skipflag(false)
|
||||
{
|
||||
manualCommandObj = ManualControlCommand::GetInstance(getObjectManager());
|
||||
manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager());
|
||||
@ -295,7 +303,7 @@ void ConfigInputWidget::openHelp()
|
||||
void ConfigInputWidget::goToWizard()
|
||||
{
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety."));
|
||||
msgBox.setText(tr("Arming Settings are now set to 'Always Disarmed' for your safety."));
|
||||
msgBox.setDetailedText(tr("You will have to reconfigure the arming settings manually "
|
||||
"when the wizard is finished. After the last step of the "
|
||||
"wizard you will be taken to the Arming Settings screen."));
|
||||
@ -307,6 +315,18 @@ void ConfigInputWidget::goToWizard()
|
||||
if(m_config->tabWidget->currentIndex() != 0) {
|
||||
m_config->tabWidget->setCurrentIndex(0);
|
||||
}
|
||||
|
||||
// Stash current manual settings data in case the wizard is
|
||||
// cancelled or the user proceeds far enough into the wizard such
|
||||
// that the UAVO is changed, but then backs out to the start and
|
||||
// chooses a different TX type (which could otherwise result in
|
||||
// unexpected TX channels being enabled)
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
previousManualSettingsData = manualSettingsData;
|
||||
manualSettingsData.Arming=ManualControlSettings::ARMING_ALWAYSDISARMED;
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
|
||||
// start the wizard
|
||||
wizardSetUpStep(wizardWelcome);
|
||||
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio);
|
||||
}
|
||||
@ -314,9 +334,9 @@ void ConfigInputWidget::goToWizard()
|
||||
void ConfigInputWidget::disableWizardButton(int value)
|
||||
{
|
||||
if(value!=0)
|
||||
m_config->configurationWizard->setVisible(false);
|
||||
m_config->groupBox_3->setVisible(false);
|
||||
else
|
||||
m_config->configurationWizard->setVisible(true);
|
||||
m_config->groupBox_3->setVisible(true);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::wzCancel()
|
||||
@ -345,12 +365,12 @@ void ConfigInputWidget::wzNext()
|
||||
// State transitions for next button
|
||||
switch(wizardStep) {
|
||||
case wizardWelcome:
|
||||
wizardSetUpStep(wizardChooseMode);
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
wizardSetUpStep(wizardChooseType);
|
||||
break;
|
||||
case wizardChooseType:
|
||||
wizardSetUpStep(wizardChooseMode);
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
wizardSetUpStep(wizardIdentifySticks);
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
@ -371,6 +391,25 @@ void ConfigInputWidget::wzNext()
|
||||
break;
|
||||
case wizardFinish:
|
||||
wizardStep=wizardNone;
|
||||
// Leave setting the throttle neutral until the final Next press,
|
||||
// else the throttle scaling causes the graphical stick movement to not
|
||||
// match the tx stick
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]=
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+
|
||||
((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]-
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02);
|
||||
if((abs(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE] -
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100) ||
|
||||
(abs(manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE] -
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100))
|
||||
{
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE]=
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]+
|
||||
(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE] -
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE])/2;
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
// move to Arming Settings tab
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
m_config->tabWidget->setCurrentIndex(2);
|
||||
break;
|
||||
@ -387,17 +426,17 @@ void ConfigInputWidget::wzBack()
|
||||
|
||||
// State transitions for next button
|
||||
switch(wizardStep) {
|
||||
case wizardChooseMode:
|
||||
case wizardChooseType:
|
||||
wizardSetUpStep(wizardWelcome);
|
||||
break;
|
||||
case wizardChooseType:
|
||||
wizardSetUpStep(wizardChooseMode);
|
||||
case wizardChooseMode:
|
||||
wizardSetUpStep(wizardChooseType);
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
prevChannel();
|
||||
if(currentChannelNum == -1) {
|
||||
wizardTearDownStep(wizardIdentifySticks);
|
||||
wizardSetUpStep(wizardChooseType);
|
||||
wizardSetUpStep(wizardChooseMode);
|
||||
}
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
@ -419,6 +458,8 @@ void ConfigInputWidget::wzBack()
|
||||
|
||||
void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
{
|
||||
m_config->wzText2->clear();
|
||||
|
||||
switch(step) {
|
||||
case wizardWelcome:
|
||||
foreach(QPointer<QWidget> wd,extraWidgets)
|
||||
@ -429,53 +470,70 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
extraWidgets.clear();
|
||||
m_config->graphicsView->setVisible(false);
|
||||
setTxMovement(nothing);
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
manualSettingsData.Arming=ManualControlSettings::ARMING_ALWAYSDISARMED;
|
||||
previousManualSettingsData = manualSettingsData;
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
m_config->wzText->setText(tr("Welcome to the inputs configuration wizard.\n"
|
||||
m_config->wzText->setText(tr("Welcome to the inputs configuration wizard.\n\n"
|
||||
"Please follow the instructions on the screen and only move your controls when asked to.\n"
|
||||
"Make sure you already configured your hardware settings on the proper tab and restarted your board.\n"
|
||||
"You can press 'back' at any time to return to the previous screeen or press 'Cancel' to quit the wizard.\n"));
|
||||
"Make sure you already configured your hardware settings on the proper tab and restarted your board.\n\n"
|
||||
"You can press 'back' at any time to return to the previous screen or press 'Cancel' to quit the wizard.\n"));
|
||||
m_config->stackedWidget->setCurrentIndex(1);
|
||||
m_config->wzBack->setEnabled(false);
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
case wizardChooseType:
|
||||
{
|
||||
m_config->graphicsView->setVisible(true);
|
||||
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio);
|
||||
setTxMovement(nothing);
|
||||
m_config->wzText->setText(tr("Please choose your transmitter type.\n"
|
||||
"Mode 1 means your throttle stick is on the right.\n"
|
||||
"Mode 2 means your throttle stick is on the left.\n"));
|
||||
m_config->wzText->setText(tr("Please choose your transmitter type:"));
|
||||
m_config->wzBack->setEnabled(true);
|
||||
QRadioButton * mode1=new QRadioButton(tr("Mode 1"),this);
|
||||
QRadioButton * mode2=new QRadioButton(tr("Mode 2"),this);
|
||||
mode2->setChecked(true);
|
||||
extraWidgets.clear();
|
||||
extraWidgets.append(mode1);
|
||||
extraWidgets.append(mode2);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(mode1);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(mode2);
|
||||
QRadioButton * typeAcro=new QRadioButton(tr("Acro: normal transmitter for fixed-wing or quad"),this);
|
||||
QRadioButton * typeHeli=new QRadioButton(tr("Helicopter: has collective pitch and throttle input"),this);
|
||||
if (transmitterType == heli) {
|
||||
typeHeli->setChecked(true);
|
||||
}
|
||||
break;
|
||||
case wizardChooseType:
|
||||
{
|
||||
m_config->wzText->setText(tr("Please choose your transmitter mode.\n"
|
||||
"Acro means normal transmitter.\n"
|
||||
"Heli means there is a collective pitch and throttle input.\n"
|
||||
"If you are using a heli transmitter please engage throttle hold now.\n"));
|
||||
m_config->wzBack->setEnabled(true);
|
||||
QRadioButton * typeAcro=new QRadioButton(tr("Acro"),this);
|
||||
QRadioButton * typeHeli=new QRadioButton(tr("Heli"),this);
|
||||
else {
|
||||
typeAcro->setChecked(true);
|
||||
typeHeli->setChecked(false);
|
||||
}
|
||||
m_config->wzText2->setText(tr("If selecting the Helicopter option, please engage throttle hold now."));
|
||||
|
||||
extraWidgets.clear();
|
||||
extraWidgets.append(typeAcro);
|
||||
extraWidgets.append(typeHeli);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(typeAcro);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(typeHeli);
|
||||
wizardStep=wizardChooseType;
|
||||
m_config->radioButtonsLayout->layout()->addWidget(typeAcro);
|
||||
m_config->radioButtonsLayout->layout()->addWidget(typeHeli);
|
||||
}
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
{
|
||||
m_config->wzBack->setEnabled(true);
|
||||
extraWidgets.clear();
|
||||
m_config->wzText->setText(tr("Please choose your transmitter mode:"));
|
||||
for (int i = 0; i <= mode4; ++i) {
|
||||
QString label;
|
||||
txMode mode = static_cast<txMode>(i);
|
||||
if (transmitterType == heli) {
|
||||
switch (mode) {
|
||||
case mode1: label = tr("Mode 1: Fore/Aft Cyclic and Yaw on the left, Throttle/Collective and Left/Right Cyclic on the right"); break;
|
||||
case mode2: label = tr("Mode 2: Throttle/Collective and Yaw on the left, Cyclic on the right"); break;
|
||||
case mode3: label = tr("Mode 3: Cyclic on the left, Throttle/Collective and Yaw on the right"); break;
|
||||
case mode4: label = tr("Mode 4: Throttle/Collective and Left/Right Cyclic on the left, Fore/Aft Cyclic and Yaw on the right"); break;
|
||||
default: Q_ASSERT(0); break;
|
||||
} }
|
||||
else {
|
||||
switch (mode) {
|
||||
case mode1: label = tr("Mode 1: Elevator and Rudder on the left, Throttle and Ailerons on the right"); break;
|
||||
case mode2: label = tr("Mode 2: Throttle and Rudder on the left, Elevator and Ailerons on the right"); break;
|
||||
case mode3: label = tr("Mode 3: Elevator and Ailerons on the left, Throttle and Rudder on the right"); break;
|
||||
case mode4: label = tr("Mode 4: Throttle and Ailerons on the left, Elevator and Rudder on the right"); break;
|
||||
default: Q_ASSERT(0); break;
|
||||
}
|
||||
m_config->wzText2->setText(tr("For a Quad: Elevator is Pitch, Ailerons are Roll, and Rudder is Yaw."));
|
||||
}
|
||||
QRadioButton * modeButton = new QRadioButton(label, this);
|
||||
if (transmitterMode == mode) {
|
||||
modeButton->setChecked(true);
|
||||
}
|
||||
extraWidgets.append(modeButton);
|
||||
m_config->radioButtonsLayout->layout()->addWidget(modeButton);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
@ -488,7 +546,8 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
setTxMovement(centerAll);
|
||||
m_config->wzText->setText(QString(tr("Please center all controls and press next when ready (if your FlightMode switch has only two positions, leave it in either position).")));
|
||||
m_config->wzText->setText(QString(tr("Please center all controls and trims and press Next when ready.\n\n"
|
||||
"If your FlightMode switch has only two positions, leave it in either position.")));
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
{
|
||||
@ -496,7 +555,7 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(),1);
|
||||
accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(),2);
|
||||
setTxMovement(nothing);
|
||||
m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions and press next when ready.")));
|
||||
m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions.\n\nPress Next when ready.")));
|
||||
fastMdata();
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
|
||||
@ -521,24 +580,22 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
dimOtherControls(true);
|
||||
setTxMovement(nothing);
|
||||
extraWidgets.clear();
|
||||
|
||||
for (int index = 0; index < manualSettingsObj->getField("ChannelMax")->getElementNames().length(); index++)
|
||||
{
|
||||
QString name = manualSettingsObj->getField("ChannelMax")->getElementNames().at(index);
|
||||
if(!name.contains("Access") && !name.contains("Flight"))
|
||||
if(!name.contains("Access") && !name.contains("Flight") &&
|
||||
(!name.contains("Collective") || transmitterType == heli))
|
||||
{
|
||||
QCheckBox * cb=new QCheckBox(name,this);
|
||||
// Make sure checked status matches current one
|
||||
cb->setChecked(manualSettingsData.ChannelMax[index] < manualSettingsData.ChannelMin[index]);
|
||||
|
||||
dynamic_cast<QGridLayout*>(m_config->checkBoxesLayout->layout())->addWidget(cb, extraWidgets.size()/4, extraWidgets.size()%4);
|
||||
extraWidgets.append(cb);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(cb);
|
||||
|
||||
connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
|
||||
}
|
||||
}
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
m_config->wzText->setText(QString(tr("Please check the picture below and correct all the sticks which show an inverted movement, press next when ready.")));
|
||||
m_config->wzText->setText(QString(tr("Please check the picture below and correct all the sticks which show an inverted movement. Press Next when ready.")));
|
||||
fastMdata();
|
||||
break;
|
||||
case wizardFinish:
|
||||
@ -546,22 +603,10 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n"
|
||||
"These new settings aren't saved to the board yet, after pressing next you will go to the Arming Settings "
|
||||
"screen where you can set your desired arming sequence and save the configuration.")));
|
||||
m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n\n"
|
||||
"IMPORTANT: These new settings have not been saved to the board yet. After pressing Next you will go to the Arming Settings "
|
||||
"tab where you can set your desired arming sequence and save the configuration.")));
|
||||
fastMdata();
|
||||
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]=
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+
|
||||
((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]-
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02);
|
||||
if((abs(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100) ||
|
||||
(abs(manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100))
|
||||
{
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE]=manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]+
|
||||
(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE])/2;
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
@ -576,16 +621,6 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
|
||||
switch(step) {
|
||||
case wizardWelcome:
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
mode=qobject_cast<QRadioButton *>(extraWidgets.at(0));
|
||||
if(mode->isChecked())
|
||||
transmitterMode=mode1;
|
||||
else
|
||||
transmitterMode=mode2;
|
||||
delete extraWidgets.at(0);
|
||||
delete extraWidgets.at(1);
|
||||
extraWidgets.clear();
|
||||
break;
|
||||
case wizardChooseType:
|
||||
type=qobject_cast<QRadioButton *>(extraWidgets.at(0));
|
||||
if(type->isChecked())
|
||||
@ -596,6 +631,16 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
|
||||
delete extraWidgets.at(1);
|
||||
extraWidgets.clear();
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
for (int i = mode1; i <= mode4; ++i) {
|
||||
mode=qobject_cast<QRadioButton *>(extraWidgets.first());
|
||||
if(mode->isChecked()) {
|
||||
transmitterMode=static_cast<txMode>(i);
|
||||
}
|
||||
delete mode;
|
||||
extraWidgets.removeFirst();
|
||||
}
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
|
||||
m_config->wzNext->setEnabled(true);
|
||||
@ -674,19 +719,19 @@ void ConfigInputWidget::restoreMdata()
|
||||
void ConfigInputWidget::setChannel(int newChan)
|
||||
{
|
||||
if(newChan == ManualControlSettings::CHANNELGROUPS_COLLECTIVE)
|
||||
m_config->wzText->setText(QString(tr("Please enable the throttle hold mode and move the collective pitch stick.")));
|
||||
m_config->wzText->setText(QString(tr("Please enable throttle hold mode.\n\nMove the Collective Pitch stick.")));
|
||||
else if (newChan == ManualControlSettings::CHANNELGROUPS_FLIGHTMODE)
|
||||
m_config->wzText->setText(QString(tr("Please toggle the flight mode switch. For switches you may have to repeat this rapidly.")));
|
||||
m_config->wzText->setText(QString(tr("Please toggle the Flight Mode switch.\n\nFor switches you may have to repeat this rapidly.")));
|
||||
else if((transmitterType == heli) && (newChan == ManualControlSettings::CHANNELGROUPS_THROTTLE))
|
||||
m_config->wzText->setText(QString(tr("Please disable throttle hold mode and move the throttle stick.")));
|
||||
m_config->wzText->setText(QString(tr("Please disable throttle hold mode.\n\nMove the Throttle stick.")));
|
||||
else
|
||||
m_config->wzText->setText(QString(tr("Please move each control once at a time according to the instructions and picture below.\n\n"
|
||||
"Move the %1 stick")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan)));
|
||||
m_config->wzText->setText(QString(tr("Please move each control one at a time according to the instructions and picture below.\n\n"
|
||||
"Move the %1 stick.")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan)));
|
||||
|
||||
if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory") ||
|
||||
manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("FlightMode")) {
|
||||
m_config->wzNext->setEnabled(true);
|
||||
m_config->wzText->setText(m_config->wzText->text() + tr(" or click next to skip this channel."));
|
||||
m_config->wzText->setText(m_config->wzText->text() + tr(" Alternatively, click Next to skip this channel."));
|
||||
} else
|
||||
m_config->wzNext->setEnabled(false);
|
||||
|
||||
@ -731,8 +776,11 @@ void ConfigInputWidget::prevChannel()
|
||||
|
||||
for (int i = 1; i < order.length(); i++) {
|
||||
if(order[i] == currentChannelNum) {
|
||||
setChannel(order[i-1]);
|
||||
if (!usedChannels.isEmpty() &&
|
||||
usedChannels.back().channelIndex == currentChannelNum) {
|
||||
usedChannels.removeLast();
|
||||
}
|
||||
setChannel(order[i-1]);
|
||||
return;
|
||||
}
|
||||
}
|
||||
@ -757,6 +805,7 @@ void ConfigInputWidget::identifyControls()
|
||||
++debounce;
|
||||
lastChannel.group= currentChannel.group;
|
||||
lastChannel.number=currentChannel.number;
|
||||
lastChannel.channelIndex = currentChannelNum;
|
||||
if(!usedChannels.contains(lastChannel) && debounce>1)
|
||||
{
|
||||
channelDetected = true;
|
||||
@ -771,7 +820,7 @@ void ConfigInputWidget::identifyControls()
|
||||
return;
|
||||
}
|
||||
|
||||
m_config->wzText->clear();
|
||||
//m_config->wzText->clear();
|
||||
setTxMovement(nothing);
|
||||
|
||||
QTimer::singleShot(2500, this, SLOT(wzNext()));
|
||||
@ -800,53 +849,56 @@ void ConfigInputWidget::identifyLimits()
|
||||
}
|
||||
void ConfigInputWidget::setMoveFromCommand(int command)
|
||||
{
|
||||
//CHANNELNUMBER_ROLL=0, CHANNELNUMBER_PITCH=1, CHANNELNUMBER_YAW=2, CHANNELNUMBER_THROTTLE=3, CHANNELNUMBER_FLIGHTMODE=4, CHANNELNUMBER_ACCESSORY0=5, CHANNELNUMBER_ACCESSORY1=6, CHANNELNUMBER_ACCESSORY2=7 } ChannelNumberElem;
|
||||
if(command==ManualControlSettings::CHANNELNUMBER_ROLL)
|
||||
{
|
||||
setTxMovement(moveRightHorizontalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_PITCH)
|
||||
{
|
||||
if(transmitterMode==mode2)
|
||||
setTxMovement(moveRightVerticalStick);
|
||||
else
|
||||
setTxMovement(moveLeftVerticalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_YAW)
|
||||
{
|
||||
setTxMovement(moveLeftHorizontalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_THROTTLE)
|
||||
{
|
||||
if(transmitterMode==mode2)
|
||||
setTxMovement(moveLeftVerticalStick);
|
||||
else
|
||||
setTxMovement(moveRightVerticalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_COLLECTIVE)
|
||||
{
|
||||
if(transmitterMode==mode2)
|
||||
setTxMovement(moveLeftVerticalStick);
|
||||
else
|
||||
setTxMovement(moveRightVerticalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_FLIGHTMODE)
|
||||
{
|
||||
setTxMovement(moveFlightMode);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY0)
|
||||
{
|
||||
setTxMovement(moveAccess0);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY1)
|
||||
{
|
||||
setTxMovement(moveAccess1);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY2)
|
||||
{
|
||||
setTxMovement(moveAccess2);
|
||||
}
|
||||
// ManualControlSettings::ChannelNumberElem:
|
||||
// CHANNELNUMBER_ROLL=0,
|
||||
// CHANNELNUMBER_PITCH=1,
|
||||
// CHANNELNUMBER_YAW=2,
|
||||
// CHANNELNUMBER_THROTTLE=3,
|
||||
// CHANNELNUMBER_FLIGHTMODE=4,
|
||||
// CHANNELNUMBER_ACCESSORY0=5,
|
||||
// CHANNELNUMBER_ACCESSORY1=6,
|
||||
// CHANNELNUMBER_ACCESSORY2=7
|
||||
|
||||
txMovements movement;
|
||||
|
||||
switch (command) {
|
||||
case ManualControlSettings::CHANNELNUMBER_ROLL:
|
||||
movement = ((transmitterMode == mode3 || transmitterMode == mode4) ?
|
||||
moveLeftHorizontalStick: moveRightHorizontalStick);
|
||||
break;
|
||||
case ManualControlSettings::CHANNELNUMBER_PITCH:
|
||||
movement = (transmitterMode == mode1 || transmitterMode == mode3) ?
|
||||
moveLeftVerticalStick: moveRightVerticalStick;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELNUMBER_YAW:
|
||||
movement = ((transmitterMode == mode1 || transmitterMode == mode2) ?
|
||||
moveLeftHorizontalStick: moveRightHorizontalStick);
|
||||
break;
|
||||
case ManualControlSettings::CHANNELNUMBER_THROTTLE:
|
||||
movement = (transmitterMode == mode2 || transmitterMode == mode4) ?
|
||||
moveLeftVerticalStick: moveRightVerticalStick;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELNUMBER_COLLECTIVE:
|
||||
movement = (transmitterMode == mode2 || transmitterMode == mode4) ?
|
||||
moveLeftVerticalStick: moveRightVerticalStick;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELNUMBER_FLIGHTMODE:
|
||||
movement = moveFlightMode;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELNUMBER_ACCESSORY0:
|
||||
movement = moveAccess0;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELNUMBER_ACCESSORY1:
|
||||
movement = moveAccess1;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELNUMBER_ACCESSORY2:
|
||||
movement = moveAccess2;
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
break;
|
||||
}
|
||||
setTxMovement(movement);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::setTxMovement(txMovements movement)
|
||||
@ -918,6 +970,7 @@ void ConfigInputWidget::setTxMovement(txMovements movement)
|
||||
animate->stop();
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -1111,19 +1164,34 @@ void ConfigInputWidget::moveSticks()
|
||||
accessoryDesiredData1=accessoryDesiredObj1->getData();
|
||||
accessoryDesiredData2=accessoryDesiredObj2->getData();
|
||||
|
||||
if(transmitterMode==mode2)
|
||||
{
|
||||
switch (transmitterMode) {
|
||||
case mode1:
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false);
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false);
|
||||
break;
|
||||
case mode2:
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false);
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false);
|
||||
}
|
||||
else
|
||||
{
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false);
|
||||
break;
|
||||
case mode3:
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false);
|
||||
m_txLeftStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false);
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false);
|
||||
break;
|
||||
case mode4:
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false);
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false);
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
break;
|
||||
}
|
||||
if(flightStatusData.FlightMode==manualSettingsData.FlightModePosition[0])
|
||||
{
|
||||
@ -1307,7 +1375,7 @@ void ConfigInputWidget::simpleCalibration(bool enable)
|
||||
m_config->configurationWizard->setEnabled(false);
|
||||
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety."));
|
||||
msgBox.setText(tr("Arming Settings are now set to 'Always Disarmed' for your safety."));
|
||||
msgBox.setDetailedText(tr("You will have to reconfigure the arming settings manually when the wizard is finished."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
@ -1337,7 +1405,7 @@ void ConfigInputWidget::simpleCalibration(bool enable)
|
||||
|
||||
restoreMdata();
|
||||
|
||||
for (int i = 0; i < ManualControlCommand::CHANNEL_NUMELEM; i++)
|
||||
for (unsigned int i = 0; i < ManualControlCommand::CHANNEL_NUMELEM; i++)
|
||||
manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i];
|
||||
|
||||
// Force flight mode neutral to middle
|
||||
|
@ -56,7 +56,7 @@ public:
|
||||
ConfigInputWidget(QWidget *parent = 0);
|
||||
~ConfigInputWidget();
|
||||
enum wizardSteps{wizardWelcome,wizardChooseMode,wizardChooseType,wizardIdentifySticks,wizardIdentifyCenter,wizardIdentifyLimits,wizardIdentifyInverted,wizardFinish,wizardNone};
|
||||
enum txMode{mode1,mode2};
|
||||
enum txMode{mode1,mode2,mode3,mode4};
|
||||
enum txMovements{moveLeftVerticalStick,moveRightVerticalStick,moveLeftHorizontalStick,moveRightHorizontalStick,moveAccess0,moveAccess1,moveAccess2,moveFlightMode,centerAll,moveAll,nothing};
|
||||
enum txMovementType{vertical,horizontal,jump,mix};
|
||||
enum txType {acro, heli};
|
||||
@ -81,6 +81,7 @@ private:
|
||||
}
|
||||
int group;
|
||||
int number;
|
||||
int channelIndex;
|
||||
}lastChannel;
|
||||
channelsStruct currentChannel;
|
||||
QList<channelsStruct> usedChannels;
|
||||
|
@ -256,30 +256,33 @@
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>90</height>
|
||||
</size>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>TextLabel</string>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="radioButtonsLayout"/>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QGridLayout" name="checkBoxesLayout"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="wzText2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_4">
|
||||
<item>
|
||||
<widget class="QGraphicsView" name="graphicsView"/>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="checkBoxesLayout"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_3">
|
||||
<item>
|
||||
|
@ -202,6 +202,7 @@ void AeroSimRCSimulator::processUpdate(const QByteArray &data)
|
||||
|
||||
/**********************************************************************************************/
|
||||
out.altitude = posZ;
|
||||
out.agl = posZ;
|
||||
out.heading = yaw * RAD2DEG;
|
||||
out.latitude = lat * 10e6;
|
||||
out.longitude = lon * 10e6;
|
||||
|
@ -268,9 +268,9 @@ void FGSimulator::processUpdate(const QByteArray& inp)
|
||||
// Get heading (deg)
|
||||
float heading = fields[14].toFloat();
|
||||
// Get altitude (m)
|
||||
float altitude = fields[15].toFloat() * FT2M;
|
||||
float altitude_msl = fields[15].toFloat() * FT2M;
|
||||
// Get altitudeAGL (m)
|
||||
float altitudeAGL = fields[16].toFloat() * FT2M;
|
||||
float altitude_agl = fields[16].toFloat() * FT2M;
|
||||
// Get groundspeed (m/s)
|
||||
float groundspeed = fields[17].toFloat() * KT2MPS;
|
||||
// Get airspeed (m/s)
|
||||
@ -299,7 +299,7 @@ void FGSimulator::processUpdate(const QByteArray& inp)
|
||||
float NED[3];
|
||||
// convert from cm back to meters
|
||||
|
||||
double LLA[3] = {latitude, longitude, altitude};
|
||||
double LLA[3] = {latitude, longitude, altitude_msl};
|
||||
double ECEF[3];
|
||||
double RNE[9];
|
||||
Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE);
|
||||
@ -310,7 +310,8 @@ void FGSimulator::processUpdate(const QByteArray& inp)
|
||||
// Update GPS Position objects
|
||||
out.latitude = latitude * 1e7;
|
||||
out.longitude = longitude * 1e7;
|
||||
out.altitude = altitude;
|
||||
out.altitude = altitude_msl;
|
||||
out.agl = altitude_agl;
|
||||
out.groundspeed = groundspeed;
|
||||
|
||||
out.calibratedAirspeed = airspeed;
|
||||
|
@ -42,7 +42,7 @@
|
||||
* can be found shipped with IL2 in the file DeviceLink.txt
|
||||
*
|
||||
* id's used in this file:
|
||||
* 30: IAS in km/h (float)
|
||||
* 30: CAS in km/h (float)
|
||||
* 32: vario in m/s (float)
|
||||
* 38: angular speed °/s (float) (which direction? azimuth?)
|
||||
* 40: barometric alt in m (float)
|
||||
@ -68,25 +68,20 @@
|
||||
#include <math.h>
|
||||
#include <qxtlogger.h>
|
||||
|
||||
const float IL2Simulator::FT2M = 0.3048;
|
||||
const float IL2Simulator::FT2M = 12*.254;
|
||||
const float IL2Simulator::KT2MPS = 0.514444444;
|
||||
const float IL2Simulator::MPS2KMH = 3.6;
|
||||
const float IL2Simulator::KMH2MPS = (1.0/3.6);
|
||||
const float IL2Simulator::INHG2KPA = 3.386;
|
||||
const float IL2Simulator::RAD2DEG = (180.0/M_PI);
|
||||
const float IL2Simulator::DEG2RAD = (M_PI/180.0);
|
||||
const float IL2Simulator::M2DEG = 60.*1852.; // 60 miles per degree times 1852 meters per mile
|
||||
const float IL2Simulator::DEG2M = (1.0/(60.*1852.));
|
||||
const float IL2Simulator::AIR_CONST = 287.058; // J/(kg*K)
|
||||
const float IL2Simulator::GROUNDDENSITY = 1.225; // kg/m³ ;)
|
||||
const float IL2Simulator::TEMP_GROUND = (15.0 + 273.0); // 15°C in Kelvin
|
||||
const float IL2Simulator::TEMP_LAPSE_RATE = -0.0065; //degrees per meter
|
||||
const float IL2Simulator::AIR_CONST_FACTOR = -0.0341631947363104; //several nature constants calculated into one
|
||||
const float IL2Simulator::NM2DEG = 60.*1852.; // 60 miles per degree times 1852 meters per mile
|
||||
const float IL2Simulator::DEG2NM = (1.0/(60.*1852.));
|
||||
|
||||
IL2Simulator::IL2Simulator(const SimulatorSettings& params) :
|
||||
Simulator(params)
|
||||
{
|
||||
|
||||
airParameters=getAirParameters();
|
||||
}
|
||||
|
||||
|
||||
@ -125,31 +120,6 @@ void IL2Simulator::transmitUpdate()
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* calculate air density from altitude
|
||||
*/
|
||||
float IL2Simulator::DENSITY(float alt) {
|
||||
return (GROUNDDENSITY * pow(
|
||||
((TEMP_GROUND+(TEMP_LAPSE_RATE*alt))/TEMP_GROUND),
|
||||
((AIR_CONST_FACTOR/TEMP_LAPSE_RATE)-1) )
|
||||
);
|
||||
}
|
||||
|
||||
/**
|
||||
* calculate air pressure from altitude
|
||||
*/
|
||||
float IL2Simulator::PRESSURE(float alt) {
|
||||
return DENSITY(alt)*(TEMP_GROUND+(alt*TEMP_LAPSE_RATE))*AIR_CONST;
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* calculate TAS from IAS and altitude
|
||||
*/
|
||||
float IL2Simulator::TAS(float IAS, float alt) {
|
||||
return (IAS*sqrt(GROUNDDENSITY/DENSITY(alt)));
|
||||
}
|
||||
|
||||
/**
|
||||
* process data string from flight simulator
|
||||
*/
|
||||
@ -171,7 +141,7 @@ void IL2Simulator::processUpdate(const QByteArray& inp)
|
||||
float value = values[1].toFloat();
|
||||
switch (id) {
|
||||
case 30:
|
||||
current.ias=value * KMH2MPS;
|
||||
current.cas=value * KMH2MPS;
|
||||
break;
|
||||
case 32:
|
||||
current.dZ=value;
|
||||
@ -206,8 +176,9 @@ void IL2Simulator::processUpdate(const QByteArray& inp)
|
||||
old.ddX=0;
|
||||
}
|
||||
|
||||
// calculate TAS from alt and IAS
|
||||
current.tas = TAS(current.ias,current.Z);
|
||||
// calculate TAS from alt and CAS
|
||||
float gravity =9.805;
|
||||
current.tas = cas2tas(current.cas, current.Z, airParameters, gravity);
|
||||
|
||||
// assume the plane actually flies straight and no wind
|
||||
// groundspeed is horizontal vector of TAS
|
||||
@ -269,7 +240,8 @@ void IL2Simulator::processUpdate(const QByteArray& inp)
|
||||
out.longitude = LLA[1] * 1e7;
|
||||
out.groundspeed = current.groundspeed;
|
||||
|
||||
out.calibratedAirspeed = current.ias;
|
||||
out.calibratedAirspeed = current.cas;
|
||||
out.trueAirspeed=cas2tas(current.cas, current.Z, airParameters, gravity);
|
||||
|
||||
out.dstN=current.Y;
|
||||
out.dstE=current.X;
|
||||
@ -277,8 +249,9 @@ void IL2Simulator::processUpdate(const QByteArray& inp)
|
||||
|
||||
// Update BaroAltitude object
|
||||
out.altitude = current.Z;
|
||||
out.temperature = TEMP_GROUND + (current.Z * TEMP_LAPSE_RATE) - 273.0;
|
||||
out.pressure = PRESSURE(current.Z)/1000.0; // kpa
|
||||
out.agl = current.Z;
|
||||
out.temperature = airParameters.groundTemp + (current.Z * airParameters.tempLapseRate) - 273.0;
|
||||
out.pressure = airPressureFromAltitude(current.Z, airParameters, gravity) ; // kpa
|
||||
|
||||
|
||||
// Update attActual object
|
||||
|
@ -51,22 +51,13 @@ private:
|
||||
static const float INHG2KPA;
|
||||
static const float RAD2DEG;
|
||||
static const float DEG2RAD;
|
||||
static const float M2DEG;
|
||||
static const float DEG2M;
|
||||
static const float AIR_CONST;
|
||||
static const float GROUNDDENSITY;
|
||||
static const float TEMP_GROUND;
|
||||
static const float TEMP_LAPSE_RATE;
|
||||
static const float AIR_CONST_FACTOR;
|
||||
|
||||
|
||||
float DENSITY(float pressure);
|
||||
float PRESSURE(float alt);
|
||||
float TAS(float ias,float alt);
|
||||
static const float NM2DEG;
|
||||
static const float DEG2NM;
|
||||
|
||||
void processUpdate(const QByteArray& data);
|
||||
float angleDifference(float a,float b);
|
||||
|
||||
AirParameters airParameters;
|
||||
};
|
||||
|
||||
class IL2SimulatorCreator : public SimulatorCreator
|
||||
|
@ -71,6 +71,15 @@ Simulator::Simulator(const SimulatorSettings& params) :
|
||||
baroAltTime = currentTime;
|
||||
airspeedActualTime=currentTime;
|
||||
|
||||
//Define standard atmospheric constants
|
||||
airParameters.univGasConstant=8.31447; //[J/(mol·K)]
|
||||
airParameters.dryAirConstant=287.058; //[J/(kg*K)]
|
||||
airParameters.groundDensity=1.225; //[kg/m^3]
|
||||
airParameters.groundTemp=15+273.15; //[K]
|
||||
airParameters.tempLapseRate=0.0065; //[deg/m]
|
||||
airParameters.M=0.0289644; //[kg/mol]
|
||||
airParameters.relativeHumidity=20; //[%]
|
||||
airParameters.seaLevelPress=101.325; //[kPa]
|
||||
}
|
||||
|
||||
Simulator::~Simulator()
|
||||
@ -152,6 +161,7 @@ void Simulator::onStart()
|
||||
gpsPos = GPSPosition::GetInstance(objManager);
|
||||
gpsVel = GPSVelocity::GetInstance(objManager);
|
||||
telStats = GCSTelemetryStats::GetInstance(objManager);
|
||||
groundTruth = GroundTruth::GetInstance(objManager);
|
||||
|
||||
// Listen to autopilot connection events
|
||||
TelemetryManager* telMngr = pm->getObject<TelemetryManager>();
|
||||
@ -392,6 +402,7 @@ void Simulator::updateUAVOs(Output2Hardware out){
|
||||
memset(&noise, 0, sizeof(Noise));
|
||||
}
|
||||
|
||||
/*******************************/
|
||||
HomeLocation::DataFields homeData = posHome->getData();
|
||||
if(!once)
|
||||
{
|
||||
@ -401,15 +412,12 @@ void Simulator::updateUAVOs(Output2Hardware out){
|
||||
// Update homelocation
|
||||
homeData.Latitude = out.latitude; //Already in *10^7 integer format
|
||||
homeData.Longitude = out.longitude; //Already in *10^7 integer format
|
||||
homeData.Altitude = out.altitude;
|
||||
homeData.Altitude = out.agl;
|
||||
double LLA[3];
|
||||
LLA[0]=out.latitude;
|
||||
LLA[1]=out.longitude;
|
||||
LLA[2]=out.altitude;
|
||||
double ECEF[3];
|
||||
double RNE[9];
|
||||
Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE);
|
||||
Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF);
|
||||
|
||||
homeData.Be[0]=0;
|
||||
homeData.Be[1]=0;
|
||||
homeData.Be[2]=0;
|
||||
@ -424,7 +432,40 @@ void Simulator::updateUAVOs(Output2Hardware out){
|
||||
once=true;
|
||||
}
|
||||
|
||||
/*******************************/
|
||||
//Copy everything to the ground truth object. GroundTruth is Noise-free.
|
||||
GroundTruth::DataFields groundTruthData;
|
||||
groundTruthData = groundTruth->getData();
|
||||
|
||||
groundTruthData.AccelerationXYZ[0]=out.accX;
|
||||
groundTruthData.AccelerationXYZ[1]=out.accY;
|
||||
groundTruthData.AccelerationXYZ[2]=out.accZ;
|
||||
|
||||
groundTruthData.AngularRates[0]=out.rollRate;
|
||||
groundTruthData.AngularRates[1]=out.pitchRate;
|
||||
groundTruthData.AngularRates[2]=out.yawRate;
|
||||
|
||||
groundTruthData.CalibratedAirspeed=out.calibratedAirspeed;
|
||||
groundTruthData.TrueAirspeed=out.trueAirspeed;
|
||||
groundTruthData.AngleOfAttack=out.angleOfAttack;
|
||||
groundTruthData.AngleOfSlip=out.angleOfSlip;
|
||||
|
||||
groundTruthData.PositionNED[0]=out.dstN-initN;
|
||||
groundTruthData.PositionNED[1]=out.dstE-initD;
|
||||
groundTruthData.PositionNED[2]=out.dstD-initD;
|
||||
|
||||
groundTruthData.VelocityNED[0]=out.velNorth;
|
||||
groundTruthData.VelocityNED[1]=out.velEast;
|
||||
groundTruthData.VelocityNED[2]=out.velDown;
|
||||
|
||||
groundTruthData.RPY[0]=out.roll;
|
||||
groundTruthData.RPY[0]=out.pitch;
|
||||
groundTruthData.RPY[0]=out.heading;
|
||||
|
||||
//Set UAVO
|
||||
groundTruth->setData(groundTruthData);
|
||||
|
||||
/*******************************/
|
||||
// Update attActual object
|
||||
AttitudeActual::DataFields attActualData;
|
||||
attActualData = attActual->getData();
|
||||
@ -574,6 +615,7 @@ void Simulator::updateUAVOs(Output2Hardware out){
|
||||
/*****************************************/
|
||||
}
|
||||
|
||||
/*******************************/
|
||||
if (settings.gcsReceiverEnabled) {
|
||||
if (gcsRcvrTime.msecsTo(currentTime) >= settings.minOutputPeriod) {
|
||||
GCSReceiver::DataFields gcsRcvrData;
|
||||
@ -591,6 +633,7 @@ void Simulator::updateUAVOs(Output2Hardware out){
|
||||
}
|
||||
|
||||
|
||||
/*******************************/
|
||||
if (settings.gpsPositionEnabled) {
|
||||
if (gpsPosTime.msecsTo(currentTime) >= settings.gpsPosRate) {
|
||||
qDebug()<< " GPS time:" << gpsPosTime << ", currentTime: " << currentTime << ", difference: " << gpsPosTime.msecsTo(currentTime);
|
||||
@ -623,6 +666,7 @@ void Simulator::updateUAVOs(Output2Hardware out){
|
||||
}
|
||||
}
|
||||
|
||||
/*******************************/
|
||||
// Update VelocityActual.{North,East,Down}
|
||||
if (settings.groundTruthEnabled) {
|
||||
if (groundTruthTime.msecsTo(currentTime) >= settings.groundTruthRate) {
|
||||
@ -645,6 +689,7 @@ void Simulator::updateUAVOs(Output2Hardware out){
|
||||
}
|
||||
}
|
||||
|
||||
// /*******************************/
|
||||
// if (settings.sonarAltitude) {
|
||||
// static QTime sonarAltTime = currentTime;
|
||||
// if (sonarAltTime.msecsTo(currentTime) >= settings.sonarAltRate) {
|
||||
@ -666,6 +711,7 @@ void Simulator::updateUAVOs(Output2Hardware out){
|
||||
// }
|
||||
// }
|
||||
|
||||
/*******************************/
|
||||
// Update BaroAltitude object
|
||||
if (settings.baroAltitudeEnabled){
|
||||
if (baroAltTime.msecsTo(currentTime) >= settings.baroAltRate) {
|
||||
@ -680,18 +726,23 @@ void Simulator::updateUAVOs(Output2Hardware out){
|
||||
}
|
||||
}
|
||||
|
||||
/*******************************/
|
||||
// Update AirspeedActual object
|
||||
if (settings.airspeedActualEnabled){
|
||||
if (airspeedActualTime.msecsTo(currentTime) >= settings.airspeedActualRate) {
|
||||
AirspeedActual::DataFields airspeedActualData;
|
||||
memset(&airspeedActualData, 0, sizeof(AirspeedActual::DataFields));
|
||||
airspeedActualData.CalibratedAirspeed = out.calibratedAirspeed + noise.airspeedActual.CalibratedAirspeed;
|
||||
airspeedActualData.TrueAirspeed = out.trueAirspeed + noise.airspeedActual.TrueAirspeed;
|
||||
airspeedActualData.alpha=out.angleOfAttack;
|
||||
airspeedActualData.beta=out.angleOfSlip;
|
||||
airspeedActual->setData(airspeedActualData);
|
||||
|
||||
airspeedActualTime=airspeedActualTime.addMSecs(settings.airspeedActualRate);
|
||||
}
|
||||
}
|
||||
|
||||
/*******************************/
|
||||
// Update raw attitude sensors
|
||||
if (settings.attRawEnabled) {
|
||||
if (attRawTime.msecsTo(currentTime) >= settings.attRawRate) {
|
||||
@ -715,3 +766,68 @@ void Simulator::updateUAVOs(Output2Hardware out){
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* calculate air density from altitude. http://en.wikipedia.org/wiki/Density_of_air
|
||||
*/
|
||||
float Simulator::airDensityFromAltitude(float alt, AirParameters air, float gravity) {
|
||||
float p= airPressureFromAltitude(alt, air, gravity);
|
||||
float rho=p*air.M/(air.univGasConstant*(air.groundTemp-air.tempLapseRate*alt));
|
||||
|
||||
return rho;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Simulator::airPressureFromAltitude Get air pressure from altitude and atmospheric conditions.
|
||||
* @param alt altitude
|
||||
* @param air atmospheric conditions
|
||||
* @param gravity
|
||||
* @return
|
||||
*/
|
||||
float Simulator::airPressureFromAltitude(float alt, AirParameters air, float gravity) {
|
||||
return air.seaLevelPress* pow(1 - air.tempLapseRate * alt /air.groundTemp, gravity * air.M/(air.univGasConstant*air.tempLapseRate));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Simulator::cas2tas calculate TAS from CAS and altitude. http://en.wikipedia.org/wiki/Airspeed
|
||||
* @param CAS Calibrated airspeed
|
||||
* @param alt altitude
|
||||
* @param air atmospheric conditions
|
||||
* @param gravity
|
||||
* @return True airspeed
|
||||
*/
|
||||
float Simulator::cas2tas(float CAS, float alt, AirParameters air, float gravity) {
|
||||
float rho=airDensityFromAltitude(alt, air, gravity);
|
||||
|
||||
return (CAS * sqrt(air.groundDensity/rho));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Simulator::tas2cas calculate CAS from TAS and altitude. http://en.wikipedia.org/wiki/Airspeed
|
||||
* @param TAS True airspeed
|
||||
* @param alt altitude
|
||||
* @param air atmospheric conditions
|
||||
* @param gravity
|
||||
* @return Calibrated airspeed
|
||||
*/
|
||||
float Simulator::tas2cas(float TAS, float alt, AirParameters air, float gravity) {
|
||||
float rho=airDensityFromAltitude(alt, air, gravity);
|
||||
|
||||
return (TAS / sqrt(air.groundDensity/rho));
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Simulator::getAirParameters get air parameters
|
||||
* @return airParameters
|
||||
*/
|
||||
AirParameters Simulator::getAirParameters(){
|
||||
return airParameters;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Simulator::setAirParameters set air parameters
|
||||
* @param airParameters
|
||||
*/
|
||||
void Simulator::setAirParameters(AirParameters airParameters){
|
||||
this->airParameters=airParameters;
|
||||
}
|
||||
|
@ -41,15 +41,16 @@
|
||||
#include "accels.h"
|
||||
#include "actuatorcommand.h"
|
||||
#include "actuatordesired.h"
|
||||
#include "airspeedactual.h"
|
||||
#include "attitudeactual.h"
|
||||
#include "attitudesettings.h"
|
||||
#include "airspeedactual.h"
|
||||
#include "baroaltitude.h"
|
||||
#include "flightstatus.h"
|
||||
#include "gcsreceiver.h"
|
||||
#include "gcstelemetrystats.h"
|
||||
#include "gpsposition.h"
|
||||
#include "gpsvelocity.h"
|
||||
#include "groundtruth.h"
|
||||
#include "gyros.h"
|
||||
#include "homelocation.h"
|
||||
#include "manualcontrolcommand.h"
|
||||
@ -69,10 +70,9 @@ typedef struct _FLIGHT_PARAM {
|
||||
float dT;
|
||||
unsigned int i;
|
||||
|
||||
// speed (relative)
|
||||
float ias;
|
||||
float cas;
|
||||
float tas;
|
||||
// speeds
|
||||
float cas; //Calibrated airspeed
|
||||
float tas; //True airspeed
|
||||
float groundspeed;
|
||||
|
||||
// position (absolute)
|
||||
@ -102,6 +102,18 @@ typedef struct _FLIGHT_PARAM {
|
||||
|
||||
} FLIGHT_PARAM;
|
||||
|
||||
struct AirParameters
|
||||
{
|
||||
float groundDensity;
|
||||
float groundTemp;
|
||||
float seaLevelPress;
|
||||
float tempLapseRate;
|
||||
float univGasConstant;
|
||||
float dryAirConstant;
|
||||
float relativeHumidity; //[%]
|
||||
float M; //Molar mass
|
||||
};
|
||||
|
||||
typedef struct _CONNECTION
|
||||
{
|
||||
QString simulatorId;
|
||||
@ -150,9 +162,13 @@ struct Output2Hardware{
|
||||
float latitude;
|
||||
float longitude;
|
||||
float altitude;
|
||||
float agl; //[m]
|
||||
float heading;
|
||||
float groundspeed; //[m/s]
|
||||
float calibratedAirspeed; //[m/s]
|
||||
float trueAirspeed; //[m/s]
|
||||
float angleOfAttack;
|
||||
float angleOfSlip;
|
||||
float roll;
|
||||
float pitch;
|
||||
float pressure;
|
||||
@ -169,7 +185,7 @@ struct Output2Hardware{
|
||||
float rollRate; //[deg/s]
|
||||
float pitchRate; //[deg/s]
|
||||
float yawRate; //[deg/s]
|
||||
float delT;
|
||||
float delT; //[s]
|
||||
|
||||
float rc_channel[GCSReceiver::CHANNEL_NUMELEM]; //Elements in rc_channel are between -1 and 1
|
||||
|
||||
@ -208,6 +224,10 @@ public:
|
||||
QString SimulatorId() const { return simulatorId; }
|
||||
void setSimulatorId(QString str) { simulatorId = str; }
|
||||
|
||||
float airDensityFromAltitude(float alt, AirParameters air, float gravity);
|
||||
float airPressureFromAltitude(float alt, AirParameters air, float gravity);
|
||||
float cas2tas(float CAS, float alt, AirParameters air, float gravity);
|
||||
float tas2cas(float TAS, float alt, AirParameters air, float gravity);
|
||||
|
||||
|
||||
static bool IsStarted() { return isStarted; }
|
||||
@ -221,6 +241,9 @@ public:
|
||||
void resetInitialHomePosition();
|
||||
void updateUAVOs(Output2Hardware out);
|
||||
|
||||
AirParameters getAirParameters();
|
||||
void setAirParameters(AirParameters airParameters);
|
||||
|
||||
signals:
|
||||
void autopilotConnected();
|
||||
void autopilotDisconnected();
|
||||
@ -275,6 +298,7 @@ protected:
|
||||
Gyros* gyros;
|
||||
GCSTelemetryStats* telStats;
|
||||
GCSReceiver* gcsReceiver;
|
||||
GroundTruth* groundTruth;
|
||||
|
||||
SimulatorSettings settings;
|
||||
|
||||
@ -311,6 +335,8 @@ private:
|
||||
void setupInputObject(UAVObject* obj, quint32 updatePeriod);
|
||||
void setupWatchedObject(UAVObject *obj, quint32 updatePeriod);
|
||||
void setupObjects();
|
||||
|
||||
AirParameters airParameters;
|
||||
};
|
||||
|
||||
|
||||
|
@ -195,7 +195,8 @@ void XplaneSimulator::transmitUpdate()
|
||||
*/
|
||||
void XplaneSimulator::processUpdate(const QByteArray& dataBuf)
|
||||
{
|
||||
float altitude = 0;
|
||||
float altitude_msl = 0;
|
||||
float altitude_agl = 0;
|
||||
float latitude = 0;
|
||||
float longitude = 0;
|
||||
float airspeed_keas = 0;
|
||||
@ -239,7 +240,8 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf)
|
||||
case XplaneSimulator::LatitudeLongitudeAltitude:
|
||||
latitude = *((float*)(buf.data()+4*1));
|
||||
longitude = *((float*)(buf.data()+4*2));
|
||||
altitude = *((float*)(buf.data()+4*3))* FT2M;
|
||||
altitude_msl = *((float*)(buf.data()+4*3))* FT2M;
|
||||
altitude_agl = *((float*)(buf.data()+4*4))* FT2M;
|
||||
break;
|
||||
|
||||
case XplaneSimulator::Speed:
|
||||
@ -302,7 +304,8 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf)
|
||||
// Update GPS Position objects
|
||||
out.latitude = latitude * 1e7;
|
||||
out.longitude = longitude * 1e7;
|
||||
out.altitude = altitude;
|
||||
out.altitude = altitude_msl;
|
||||
out.agl = altitude_agl;
|
||||
out.groundspeed = groundspeed_ktgs*1.15*1.6089/3.6; //Convert from [kts] to [m/s]
|
||||
|
||||
out.calibratedAirspeed = airspeed_keas*1.15*1.6089/3.6; //Convert from [kts] to [m/s]
|
||||
|
@ -100,7 +100,7 @@ bool flightDataModel::setColumnByIndex(pathPlanData *row,const int index,const
|
||||
return true;
|
||||
break;
|
||||
case ISRELATIVE:
|
||||
row->isRelative=value.toDouble();
|
||||
row->isRelative=value.toBool();
|
||||
return true;
|
||||
break;
|
||||
case ALTITUDE:
|
||||
@ -116,19 +116,19 @@ bool flightDataModel::setColumnByIndex(pathPlanData *row,const int index,const
|
||||
return true;
|
||||
break;
|
||||
case MODE_PARAMS0:
|
||||
row->mode_params[0]=value.toInt();
|
||||
row->mode_params[0]=value.toFloat();
|
||||
return true;
|
||||
break;
|
||||
case MODE_PARAMS1:
|
||||
row->mode_params[1]=value.toInt();
|
||||
row->mode_params[1]=value.toFloat();
|
||||
return true;
|
||||
break;
|
||||
case MODE_PARAMS2:
|
||||
row->mode_params[2]=value.toInt();
|
||||
row->mode_params[2]=value.toFloat();
|
||||
return true;
|
||||
break;
|
||||
case MODE_PARAMS3:
|
||||
row->mode_params[3]=value.toInt();
|
||||
row->mode_params[3]=value.toFloat();
|
||||
return true;
|
||||
break;
|
||||
case CONDITION:
|
||||
@ -136,19 +136,19 @@ bool flightDataModel::setColumnByIndex(pathPlanData *row,const int index,const
|
||||
return true;
|
||||
break;
|
||||
case CONDITION_PARAMS0:
|
||||
row->condition_params[0]=value.toInt();
|
||||
row->condition_params[0]=value.toFloat();
|
||||
return true;
|
||||
break;
|
||||
case CONDITION_PARAMS1:
|
||||
row->condition_params[1]=value.toInt();
|
||||
row->condition_params[1]=value.toFloat();
|
||||
return true;
|
||||
break;
|
||||
case CONDITION_PARAMS2:
|
||||
row->condition_params[2]=value.toInt();
|
||||
row->condition_params[2]=value.toFloat();
|
||||
return true;
|
||||
break;
|
||||
case CONDITION_PARAMS3:
|
||||
row->condition_params[3]=value.toInt();
|
||||
row->condition_params[3]=value.toFloat();
|
||||
return true;
|
||||
break;
|
||||
case COMMAND:
|
||||
@ -366,15 +366,15 @@ bool flightDataModel::insertRows(int row, int count, const QModelIndex &/*parent
|
||||
data->disRelative=0;
|
||||
data->beaRelative=0;
|
||||
data->altitudeRelative=0;
|
||||
data->isRelative=0;
|
||||
data->isRelative=true;
|
||||
data->altitude=0;
|
||||
data->velocity=0;
|
||||
data->mode=0;
|
||||
data->mode=1;
|
||||
data->mode_params[0]=0;
|
||||
data->mode_params[1]=0;
|
||||
data->mode_params[2]=0;
|
||||
data->mode_params[3]=0;
|
||||
data->condition=0;
|
||||
data->condition=3;
|
||||
data->condition_params[0]=0;
|
||||
data->condition_params[1]=0;
|
||||
data->condition_params[2]=0;
|
||||
@ -383,6 +383,25 @@ bool flightDataModel::insertRows(int row, int count, const QModelIndex &/*parent
|
||||
data->jumpdestination=0;
|
||||
data->errordestination=0;
|
||||
data->locked=false;
|
||||
if(rowCount()>0)
|
||||
{
|
||||
data->altitude=this->data(this->index(rowCount()-1,ALTITUDE)).toDouble();
|
||||
data->altitudeRelative=this->data(this->index(rowCount()-1,ALTITUDERELATIVE)).toDouble();
|
||||
data->isRelative=this->data(this->index(rowCount()-1,ISRELATIVE)).toBool();
|
||||
data->velocity=this->data(this->index(rowCount()-1,VELOCITY)).toFloat();
|
||||
data->mode=this->data(this->index(rowCount()-1,MODE)).toInt();
|
||||
data->mode_params[0]=this->data(this->index(rowCount()-1,MODE_PARAMS0)).toFloat();
|
||||
data->mode_params[1]=this->data(this->index(rowCount()-1,MODE_PARAMS1)).toFloat();
|
||||
data->mode_params[2]=this->data(this->index(rowCount()-1,MODE_PARAMS2)).toFloat();
|
||||
data->mode_params[3]=this->data(this->index(rowCount()-1,MODE_PARAMS3)).toFloat();
|
||||
data->condition=this->data(this->index(rowCount()-1,CONDITION)).toInt();
|
||||
data->condition_params[0]=this->data(this->index(rowCount()-1,CONDITION_PARAMS0)).toFloat();
|
||||
data->condition_params[1]=this->data(this->index(rowCount()-1,CONDITION_PARAMS1)).toFloat();
|
||||
data->condition_params[2]=this->data(this->index(rowCount()-1,CONDITION_PARAMS2)).toFloat();
|
||||
data->condition_params[3]=this->data(this->index(rowCount()-1,CONDITION_PARAMS3)).toFloat();
|
||||
data->command=this->data(this->index(rowCount()-1,COMMAND)).toInt();
|
||||
data->errordestination=this->data(this->index(rowCount()-1,ERRORDESTINATION)).toInt();
|
||||
}
|
||||
dataStorage.insert(row,data);
|
||||
}
|
||||
endInsertRows();
|
||||
@ -601,13 +620,13 @@ void flightDataModel::readFromFile(QString fileName)
|
||||
else if(field.attribute("name")=="mode")
|
||||
data->mode=field.attribute("value").toInt();
|
||||
else if(field.attribute("name")=="mode_param0")
|
||||
data->mode_params[0]=field.attribute("value").toDouble();
|
||||
data->mode_params[0]=field.attribute("value").toFloat();
|
||||
else if(field.attribute("name")=="mode_param1")
|
||||
data->mode_params[1]=field.attribute("value").toDouble();
|
||||
data->mode_params[1]=field.attribute("value").toFloat();
|
||||
else if(field.attribute("name")=="mode_param2")
|
||||
data->mode_params[2]=field.attribute("value").toDouble();
|
||||
data->mode_params[2]=field.attribute("value").toFloat();
|
||||
else if(field.attribute("name")=="mode_param3")
|
||||
data->mode_params[3]=field.attribute("value").toDouble();
|
||||
data->mode_params[3]=field.attribute("value").toFloat();
|
||||
else if(field.attribute("name")=="condition")
|
||||
data->condition=field.attribute("value").toDouble();
|
||||
else if(field.attribute("name")=="condition_param0")
|
||||
|
@ -40,7 +40,6 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstract
|
||||
connect(ui->checkBoxLocked,SIGNAL(toggled(bool)),this,SLOT(enableEditWidgets(bool)));
|
||||
connect(ui->cbMode,SIGNAL(currentIndexChanged(int)),this,SLOT(setupModeWidgets()));
|
||||
connect(ui->cbCondition,SIGNAL(currentIndexChanged(int)),this,SLOT(setupConditionWidgets()));
|
||||
connect(ui->pushButtonApply,SIGNAL(clicked()),this,SLOT(pushButtonApply_clicked()));
|
||||
connect(ui->pushButtonCancel,SIGNAL(clicked()),this,SLOT(pushButtonCancel_clicked()));
|
||||
MapDataDelegate::loadComboBox(ui->cbMode,flightDataModel::MODE);
|
||||
MapDataDelegate::loadComboBox(ui->cbCondition,flightDataModel::CONDITION);
|
||||
@ -50,7 +49,7 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstract
|
||||
mapper->setItemDelegate(new MapDataDelegate(this));
|
||||
connect(mapper,SIGNAL(currentIndexChanged(int)),this,SLOT(currentIndexChanged(int)));
|
||||
mapper->setModel(model);
|
||||
mapper->setSubmitPolicy(QDataWidgetMapper::ManualSubmit);
|
||||
mapper->setSubmitPolicy(QDataWidgetMapper::AutoSubmit);
|
||||
mapper->addMapping(ui->checkBoxLocked,flightDataModel::LOCKED);
|
||||
mapper->addMapping(ui->doubleSpinBoxLatitude,flightDataModel::LATPOSITION);
|
||||
mapper->addMapping(ui->doubleSpinBoxLongitude,flightDataModel::LNGPOSITION);
|
||||
@ -234,10 +233,6 @@ void opmap_edit_waypoint_dialog::pushButtonCancel_clicked()
|
||||
mapper->revert();
|
||||
close();
|
||||
}
|
||||
void opmap_edit_waypoint_dialog::pushButtonApply_clicked()
|
||||
{
|
||||
mapper->submit();
|
||||
}
|
||||
void opmap_edit_waypoint_dialog::editWaypoint(mapcontrol::WayPointItem *waypoint_item)
|
||||
{
|
||||
if (!waypoint_item) return;
|
||||
|
@ -64,7 +64,6 @@ private slots:
|
||||
void setupConditionWidgets();
|
||||
void pushButtonCancel_clicked();
|
||||
void on_pushButtonOK_clicked();
|
||||
void pushButtonApply_clicked();
|
||||
void on_pushButton_clicked();
|
||||
void on_pushButton_2_clicked();
|
||||
void enableEditWidgets(bool);
|
||||
|
@ -386,6 +386,9 @@
|
||||
<property name="maximum">
|
||||
<double>999999999.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.010000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
@ -469,6 +472,9 @@
|
||||
<property name="maximum">
|
||||
<double>999999999.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.010000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
@ -476,6 +482,9 @@
|
||||
<property name="maximum">
|
||||
<double>999999999.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.010000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
@ -483,6 +492,9 @@
|
||||
<property name="maximum">
|
||||
<double>999999999.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.010000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
@ -545,6 +557,9 @@
|
||||
<property name="maximum">
|
||||
<double>999999999.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.010000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
@ -628,6 +643,9 @@
|
||||
<property name="maximum">
|
||||
<double>999999999.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.010000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
@ -635,6 +653,9 @@
|
||||
<property name="maximum">
|
||||
<double>999999999.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.010000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
@ -642,6 +663,9 @@
|
||||
<property name="maximum">
|
||||
<double>999999999.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>0.010000000000000</double>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
@ -798,13 +822,6 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="pushButtonApply">
|
||||
<property name="text">
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="pushButtonCancel">
|
||||
<property name="text">
|
||||
|
@ -72,6 +72,7 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \
|
||||
$$UAVOBJECT_SYNTHETICS/mixerstatus.h \
|
||||
$$UAVOBJECT_SYNTHETICS/velocitydesired.h \
|
||||
$$UAVOBJECT_SYNTHETICS/velocityactual.h \
|
||||
$$UAVOBJECT_SYNTHETICS/groundtruth.h \
|
||||
$$UAVOBJECT_SYNTHETICS/fixedwingpathfollowersettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/fixedwingpathfollowerstatus.h \
|
||||
$$UAVOBJECT_SYNTHETICS/vtolpathfollowersettings.h \
|
||||
@ -152,6 +153,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/mixerstatus.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/velocitydesired.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/velocityactual.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/groundtruth.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/fixedwingpathfollowersettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/fixedwingpathfollowerstatus.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/vtolpathfollowersettings.cpp \
|
||||
|
@ -8,8 +8,8 @@
|
||||
<field name="RxFailures" units="count" type="uint32" elements="1"/>
|
||||
<field name="TxRetries" units="count" type="uint32" elements="1"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="manual" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="periodic" period="5000"/>
|
||||
<telemetrygcs acked="false" updatemode="manual" period="0"/>
|
||||
<telemetryflight acked="false" updatemode="periodic" period="5000"/>
|
||||
<logging updatemode="periodic" period="5000"/>
|
||||
</object>
|
||||
</xml>
|
||||
|
@ -8,8 +8,8 @@
|
||||
<field name="RxFailures" units="count" type="uint32" elements="1"/>
|
||||
<field name="TxRetries" units="count" type="uint32" elements="1"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="periodic" period="5000"/>
|
||||
<telemetryflight acked="true" updatemode="manual" period="0"/>
|
||||
<telemetrygcs acked="false" updatemode="periodic" period="5000"/>
|
||||
<telemetryflight acked="false" updatemode="manual" period="0"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
</xml>
|
||||
|
@ -1,10 +0,0 @@
|
||||
<xml>
|
||||
<object name="GPSSettings" singleinstance="true" settings="true">
|
||||
<description>Settings for the GPS</description>
|
||||
<field name="DataProtocol" units="" type="enum" elements="1" options="NMEA,UBX" defaultvalue="UBX"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
</xml>
|
18
shared/uavobjectdefinition/groundtruth.xml
Normal file
18
shared/uavobjectdefinition/groundtruth.xml
Normal file
@ -0,0 +1,18 @@
|
||||
<xml>
|
||||
<object name="GroundTruth" singleinstance="true" settings="false">
|
||||
<description>Ground truth data output by a simulator.</description>
|
||||
<field name="AccelerationXYZ" units="m/s^2" type="float" elements="3"/>
|
||||
<field name="PositionNED" units="m" type="float" elements="3"/>
|
||||
<field name="VelocityNED" units="m/s" type="float" elements="3"/>
|
||||
<field name="RPY" units="deg" type="float" elements="3"/>
|
||||
<field name="AngularRates" units="deg/s" type="float" elements="3"/>
|
||||
<field name="TrueAirspeed" units="m/s" type="float" elements="1"/>
|
||||
<field name="CalibratedAirspeed" units="m/s" type="float" elements="1"/>
|
||||
<field name="AngleOfAttack" units="deg" type="float" elements="1"/>
|
||||
<field name="AngleOfSlip" units="deg" type="float" elements="1"/>
|
||||
<access gcs="readwrite" flight="readonly"/>
|
||||
<telemetrygcs acked="false" updatemode="periodic" period="50"/>
|
||||
<telemetryflight acked="false" updatemode="manual" period="50000"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
</xml>
|
@ -3,6 +3,7 @@
|
||||
<description>Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand</description>
|
||||
<field name="AirframeType" units="" type="enum" elements="1" options="FixedWing,FixedWingElevon,FixedWingVtail,VTOL,HeliCP,QuadX,QuadP,Hexa,Octo,Custom,HexaX,OctoV,OctoCoaxP,OctoCoaxX,HexaCoax,Tri,GroundVehicleCar,GroundVehicleDifferential,GroundVehicleMotorcycle" defaultvalue="QuadX"/>
|
||||
<field name="GUIConfigData" units="bits" type="uint32" elements="4" defaultvalue="0"/>
|
||||
<field name="GPSDataProtocol" units="" type="enum" elements="1" options="NMEA,UBX" defaultvalue="UBX"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
|
Loading…
Reference in New Issue
Block a user