From 35fb0b3c6a9b7def8b0371f8bed710fb667762b8 Mon Sep 17 00:00:00 2001 From: zedamota Date: Sun, 12 Feb 2012 16:26:31 +0000 Subject: [PATCH 01/52] Fixes BT telemetry not working on non Windows OSs Signed-off-by: James Cotton --- .../plugins/serialconnection/serialplugin.cpp | 22 +++++-- .../serialconnection/serialpluginoptions.ui | 58 +------------------ .../serialpluginoptionspage.cpp | 32 ++++++++++ 3 files changed, 50 insertions(+), 62 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp b/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp index 23bb8f9f9..f83efe968 100644 --- a/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp @@ -205,31 +205,43 @@ void SerialConnection::resumePolling() } BaudRateType SerialConnection::stringToBaud(QString str) -{ +{ if(str=="1200") return BAUD1200; + if(str=="1800") + return BAUD1800; else if(str=="2400") - return BAUD1200; - else if(str== "4800") return BAUD2400; + else if(str== "4800") + return BAUD4800; else if(str== "9600") return BAUD9600; + else if(str== "14400") + return BAUD14400; else if(str== "19200") return BAUD19200; else if(str== "38400") return BAUD38400; - else if(str== "57600") + else if(str== "56000") return BAUD56000; + else if(str== "57600") + return BAUD57600; + else if(str== "76800") + return BAUD76800; else if(str== "115200") return BAUD115200; + else if(str== "128000") + return BAUD128000; else if(str== "230400") return BAUD230400; + else if(str== "256000") + return BAUD256000; else if(str== "460800") return BAUD460800; else if(str== "921600") return BAUD921600; else - return BAUD56000; + return BAUD57600; } SerialPlugin::SerialPlugin() diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui index 04f9faf06..1aedd7e2c 100644 --- a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui @@ -22,63 +22,7 @@ - - - - 1200 - - - - - 2400 - - - - - 4800 - - - - - 9600 - - - - - 19200 - - - - - 38400 - - - - - 57600 - - - - - 115200 - - - - - 230400 - - - - - 460800 - - - - - 921600 - - - + diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.cpp b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.cpp index 29d8b3784..bd46dbb47 100644 --- a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.cpp @@ -47,6 +47,38 @@ QWidget *SerialPluginOptionsPage::createPage(QWidget *parent) QWidget *optionsPageWidget = new QWidget; //main layout options_page->setupUi(optionsPageWidget); + QStringList allowedSpeeds; + allowedSpeeds<<"1200" +#ifdef Q_OS_UNIX + <<"1800" //POSIX ONLY +#endif + <<"2400" + <<"4800" + <<"9600" +#ifdef Q_OS_WIN + <<"14400" //WINDOWS ONLY +#endif + <<"19200" + <<"38400" +#ifdef Q_OS_WIN + <<"56000" //WINDOWS ONLY +#endif + <<"57600" +#ifdef Q_OS_UNIX + <<"76800" //POSIX ONLY +#endif + <<"115200" +#ifdef Q_OS_WIN + <<"128000" //WINDOWS ONLY + <<"230400" //WINDOWS ONLY + <<"256000" //WINDOWS ONLY + <<"460800" //WINDOWS ONLY + <<"921600" //WINDOWS ONLY +#endif + ; + + + options_page->cb_speed->addItems(allowedSpeeds); options_page->cb_speed->setCurrentIndex(options_page->cb_speed->findText(m_config->speed())); return optionsPageWidget; } From 319e834d32293e1a5fb05a0fe791839da6095194 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Sat, 18 Feb 2012 08:38:01 +1100 Subject: [PATCH 02/52] Update Plist info for Mac --- ground/openpilotgcs/src/app/Info.plist | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/app/Info.plist b/ground/openpilotgcs/src/app/Info.plist index 23e542b6d..297c81b5c 100644 --- a/ground/openpilotgcs/src/app/Info.plist +++ b/ground/openpilotgcs/src/app/Info.plist @@ -172,7 +172,7 @@ CFBundleGetInfoString - Qt Creator; Copyright Nokia Corporation + OpenPilot GCS; Copyright OpenPilot CFBundleIconFile @ICON@ CFBundlePackageType @@ -182,7 +182,7 @@ CFBundleExecutable @EXECUTABLE@ CFBundleIdentifier - com.nokia.qtcreator + org.openpilot.openpilotgcs CFBundleVersion 1.3.1 CFBundleShortVersionString From 1d1915d2be8a84551ed0b673bb198ae80dca2622 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Thu, 12 Jul 2012 01:41:24 +0300 Subject: [PATCH 03/52] GCS Input widget: make RC inputs the default tab --- ground/openpilotgcs/src/plugins/config/input.ui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index e00f4baf3..199f52620 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -17,7 +17,7 @@ - 1 + 0 From 43bd9a88190102f78fb099c0f5510d69b3723da1 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 13 Jul 2012 00:14:50 +0300 Subject: [PATCH 04/52] nsis: add some translations for DE (thanks, D-Lite) --- package/winx86/translations/strings_de.nsh | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/package/winx86/translations/strings_de.nsh b/package/winx86/translations/strings_de.nsh index 2eea9dd8d..234a1fe3a 100644 --- a/package/winx86/translations/strings_de.nsh +++ b/package/winx86/translations/strings_de.nsh @@ -31,9 +31,9 @@ LangString DESC_InSecSounds ${LANG_GERMAN} "GCS Sounddateien (benötigt für akustische Ereignisbenachrichtigungen)." LangString DESC_InSecLocalization ${LANG_GERMAN} "GCS Lokalisierung (für unterstützte Sprachen)." LangString DESC_InSecFirmware ${LANG_GERMAN} "OpenPilot firmware binaries." - LangString DESC_InSecUtilities ${LANG_GERMAN} "OpenPilot utilities (Matlab log parser)." - LangString DESC_InSecDrivers ${LANG_GERMAN} "OpenPilot hardware driver files (optional OpenPilot CDC driver)." - LangString DESC_InSecInstallDrivers ${LANG_GERMAN} "Install OpenPilot CDC driver (optional)." + LangString DESC_InSecUtilities ${LANG_GERMAN} "OpenPilot Dienstprogramme (Matlab Log Parser)." + LangString DESC_InSecDrivers ${LANG_GERMAN} "OpenPilot Hardware Treiberdateien (optionaler OpenPilot CDC Treiber)." + LangString DESC_InSecInstallDrivers ${LANG_GERMAN} "Installiere OpenPilot CDC Treiber (optional)." LangString DESC_InSecShortcuts ${LANG_GERMAN} "Installiere Verknüpfungen unter Startmenü->Anwendungen." ;-------------------------------- From 9507a79c6ddf119b5db951fa696e27a421316e11 Mon Sep 17 00:00:00 2001 From: Mike LaBranche Date: Mon, 16 Jul 2012 13:08:12 -0700 Subject: [PATCH 05/52] MultiRotor Config, Bugfix: include TriYaw channel in getChannelDescriptions --- .../plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index d27f4c530..bfa4fe7a2 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -274,6 +274,8 @@ QStringList ConfigMultiRotorWidget::getChannelDescriptions() channelDesc[multi.VTOLMotorW-1] = QString("VTOLMotorW"); if (multi.VTOLMotorE > 0 && multi.VTOLMotorE < ConfigMultiRotorWidget::CHANNEL_NUMELEM) channelDesc[multi.VTOLMotorE-1] = QString("VTOLMotorE"); + if (multi.TRIYaw > 0 && multi.TRIYaw <= ConfigMultiRotorWidget::CHANNEL_NUMELEM) + channelDesc[multi.TRIYaw-1] = QString("Tri-Yaw"); return channelDesc; } From 86d672473911c9c84769d98d1973ff76723e3aa6 Mon Sep 17 00:00:00 2001 From: David Date: Thu, 19 Jul 2012 07:02:49 +1000 Subject: [PATCH 06/52] Change the wording to be less harsh --- ground/openpilotgcs/src/plugins/config/airframe.ui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index 47006a789..ba3396ac7 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -2788,7 +2788,7 @@ p, li { white-space: pre-wrap; } <table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> <tr> <td style="border: none;"> -<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD IS DANGEROUS</span></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD NEEDS CAUTION</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</p> <p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</p></td></tr></table></body></html> From dc1a8205cadbb6579d881d6ce1cbaa41457fd464 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 13 Jun 2012 00:31:59 -0500 Subject: [PATCH 07/52] Allow building an unsigned linux package until we have official OP signing keys --- package/Makefile.linux | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package/Makefile.linux b/package/Makefile.linux index 78e902d71..086079905 100644 --- a/package/Makefile.linux +++ b/package/Makefile.linux @@ -42,7 +42,7 @@ DEB_PACKAGE_NAME := openpilot_$(VERSION_FULL)_$(DEB_PLATFORM) linux_deb_package: deb_build gcs @echo $@ starting - cd .. && dpkg-buildpackage -b + cd .. && dpkg-buildpackage -b -us -uc $(V1)mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).deb $(BUILD_DIR) $(V1)mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(BUILD_DIR) $(V1)rm -rf $(DEB_BUILD_DIR) From 4e42fb564e372a8e60f4b77eaf4dab5ec0deee7a Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 22 Jul 2012 14:18:49 +0300 Subject: [PATCH 08/52] AeroSimRC: fix CC3D virtual sensor readings in simulation mode --- flight/Modules/Attitude/attitude.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index 02ba45744..baa0c5453 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -375,6 +375,10 @@ static int32_t updateSensorsCC3D(AccelsData * accelsData, GyrosData * gyrosData) if(xQueueReceive(queue, (void *) &mpu6000_data, SENSOR_PERIOD) == errQUEUE_EMPTY) return -1; // Error, no data + // Do not read raw sensor data in simulation mode + if (GyrosReadOnly() || AccelsReadOnly()) + return 0; + gyros[0] = -mpu6000_data.gyro_y * PIOS_MPU6000_GetScale(); gyros[1] = -mpu6000_data.gyro_x * PIOS_MPU6000_GetScale(); gyros[2] = -mpu6000_data.gyro_z * PIOS_MPU6000_GetScale(); From 545018244c5af9b521ecd7e8a83a75a1bb484cff Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 22 Jul 2012 23:03:27 -0500 Subject: [PATCH 09/52] Make saving occur within the system thread instead of the event system thread --- flight/Modules/System/systemmod.c | 21 ++++++++++++--------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 827b264d2..7d0118583 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -73,6 +73,7 @@ static uint32_t idleCounter; static uint32_t idleCounterClear; static xTaskHandle systemTaskHandle; +static xQueueHandle objectPersistenceQueue; static bool stackOverflow; static bool mallocFailed; @@ -124,6 +125,8 @@ int32_t SystemModInitialize(void) SystemModStart(); + objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + return 0; } @@ -133,8 +136,6 @@ MODULE_INITCALL(SystemModInitialize, 0) */ static void systemTask(void *parameters) { - portTickType lastSysTime; - /* create all modules thread */ MODULE_TASKCREATE_ALL; @@ -154,10 +155,9 @@ static void systemTask(void *parameters) // Initialize vars idleCounter = 0; idleCounterClear = 0; - lastSysTime = xTaskGetTickCount(); // Listen for SettingPersistance object updates, connect a callback function - ObjectPersistenceConnectCallback(&objectUpdatedCb); + ObjectPersistenceConnectQueue(objectPersistenceQueue); // Main system loop while (1) { @@ -193,11 +193,14 @@ static void systemTask(void *parameters) FlightStatusData flightStatus; FlightStatusGet(&flightStatus); - // Wait until next period - if(flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) { - vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2) ); - } else { - vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS); + UAVObjEvent ev; + int delayTime = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED ? + SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2) : + SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS; + + if(xQueueReceive(objectPersistenceQueue, &ev, delayTime) == pdTRUE) { + // If object persistence is updated call the callback + objectUpdatedCb(&ev); } } } From e38325c745a1a8e0962e22fdc247c97f75134a31 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 23 Jul 2012 08:47:43 -0500 Subject: [PATCH 10/52] Should check that the queue allocates and initialize shoudl return -1 if not --- flight/Modules/System/systemmod.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 7d0118583..005a0c565 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -126,6 +126,8 @@ int32_t SystemModInitialize(void) SystemModStart(); objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + if (objectPersistenceQueue == NULL) + return -1; return 0; } From 9865466da9ddc556d645cc5a93c17f9463d48f41 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 09:51:03 -0500 Subject: [PATCH 11/52] Make sure to create the system queue BEFORE calling task start. Systemmod initializes differently than other threads and I missed htat. Huge thanks to Hyper for making me realize that despite the fact I didn't see it :D. --- flight/Modules/System/systemmod.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 005a0c565..33bf462fb 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -123,12 +123,12 @@ int32_t SystemModInitialize(void) WatchdogStatusInitialize(); #endif - SystemModStart(); - objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); if (objectPersistenceQueue == NULL) return -1; + SystemModStart(); + return 0; } From 66191c4d0128823c321c8b858cbea97a8c13999d Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 22 Jul 2012 23:03:27 -0500 Subject: [PATCH 12/52] Make saving occur within the system thread instead of the event system thread --- flight/Modules/System/systemmod.c | 21 ++++++++++++--------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 827b264d2..7d0118583 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -73,6 +73,7 @@ static uint32_t idleCounter; static uint32_t idleCounterClear; static xTaskHandle systemTaskHandle; +static xQueueHandle objectPersistenceQueue; static bool stackOverflow; static bool mallocFailed; @@ -124,6 +125,8 @@ int32_t SystemModInitialize(void) SystemModStart(); + objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + return 0; } @@ -133,8 +136,6 @@ MODULE_INITCALL(SystemModInitialize, 0) */ static void systemTask(void *parameters) { - portTickType lastSysTime; - /* create all modules thread */ MODULE_TASKCREATE_ALL; @@ -154,10 +155,9 @@ static void systemTask(void *parameters) // Initialize vars idleCounter = 0; idleCounterClear = 0; - lastSysTime = xTaskGetTickCount(); // Listen for SettingPersistance object updates, connect a callback function - ObjectPersistenceConnectCallback(&objectUpdatedCb); + ObjectPersistenceConnectQueue(objectPersistenceQueue); // Main system loop while (1) { @@ -193,11 +193,14 @@ static void systemTask(void *parameters) FlightStatusData flightStatus; FlightStatusGet(&flightStatus); - // Wait until next period - if(flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) { - vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2) ); - } else { - vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS); + UAVObjEvent ev; + int delayTime = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED ? + SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2) : + SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS; + + if(xQueueReceive(objectPersistenceQueue, &ev, delayTime) == pdTRUE) { + // If object persistence is updated call the callback + objectUpdatedCb(&ev); } } } From c0c5da69aa4262b6f1cdaa09906c32c116d42a1b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 23 Jul 2012 08:47:43 -0500 Subject: [PATCH 13/52] Should check that the queue allocates and initialize shoudl return -1 if not --- flight/Modules/System/systemmod.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 7d0118583..005a0c565 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -126,6 +126,8 @@ int32_t SystemModInitialize(void) SystemModStart(); objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); + if (objectPersistenceQueue == NULL) + return -1; return 0; } From f9eb82478bf62e03d72aa75147413266f0501dfd Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 24 Jul 2012 09:51:03 -0500 Subject: [PATCH 14/52] Make sure to create the system queue BEFORE calling task start. Systemmod initializes differently than other threads and I missed htat. Huge thanks to Hyper for making me realize that despite the fact I didn't see it :D. --- flight/Modules/System/systemmod.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 005a0c565..33bf462fb 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -123,12 +123,12 @@ int32_t SystemModInitialize(void) WatchdogStatusInitialize(); #endif - SystemModStart(); - objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent)); if (objectPersistenceQueue == NULL) return -1; + SystemModStart(); + return 0; } From 4003cd70a893c612c517497b2be05e58fb174772 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 27 Jul 2012 11:55:01 +0100 Subject: [PATCH 15/52] GCS-Made rate Kd roll and pitch link when checkbox is checked. --- .../src/plugins/config/configstabilizationwidget.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 331c39e23..b54bdbc44 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -135,6 +135,14 @@ void ConfigStabilizationWidget::processLinkedWidgets(QWidget * widget) { m_stabilization->RateRollILimit_2->setValue(m_stabilization->RatePitchILimit->value()); } + else if(widget== m_stabilization->RollRateKd) + { + m_stabilization->PitchRateKd->setValue(m_stabilization->RollRateKd->value()); + } + else if(widget== m_stabilization->PitchRateKd) + { + m_stabilization->RollRateKd->setValue(m_stabilization->PitchRateKd->value()); + } } if(m_stabilization->checkBox_8->checkState()==Qt::Checked) { From 1955e8b84275f02f48bac6986fc60926995d40de Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 27 Jul 2012 11:45:58 +0100 Subject: [PATCH 16/52] GCS-Comment out the updated statements on vehicleconfig.cpp TODO check if this brings other problems. REVERT commit if it does --- .../src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp index 94c3111b3..7c9ca86e1 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -105,7 +105,7 @@ void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) { systemSettingsData.GUIConfigData[i] = configData.UAVObject[i]; systemSettings->setData(systemSettingsData); - systemSettings->updated(); + //systemSettings->updated(); //emit ConfigurationChanged(); } @@ -180,7 +180,8 @@ void VehicleConfig::setMixerType(UAVDataObject* mixer, int channel, MixerTypeEle if (mixerType >= 0 && mixerType < mixerTypeDescriptions.count()) { field->setValue(mixerTypeDescriptions[mixerType]); - mixer->updated(); + // mixer->updated(); + qDebug()<<"updateMixer"; } } } @@ -228,7 +229,7 @@ void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, Mixer if (field) { field->setDouble(value, elementName); - mixer->updated(); + //mixer->updated(); } } } From bf6790f554e8f61b3c0c033950e4ad703f9b44fc Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 27 Jul 2012 18:42:20 +0100 Subject: [PATCH 17/52] GCS-Made the changes to vehicleconfig final and reenabled the system settings update call. --- .../src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp index 7c9ca86e1..fe76f1660 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.cpp @@ -105,7 +105,7 @@ void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) { systemSettingsData.GUIConfigData[i] = configData.UAVObject[i]; systemSettings->setData(systemSettingsData); - //systemSettings->updated(); + systemSettings->updated(); //emit ConfigurationChanged(); } @@ -180,8 +180,6 @@ void VehicleConfig::setMixerType(UAVDataObject* mixer, int channel, MixerTypeEle if (mixerType >= 0 && mixerType < mixerTypeDescriptions.count()) { field->setValue(mixerTypeDescriptions[mixerType]); - // mixer->updated(); - qDebug()<<"updateMixer"; } } } @@ -229,7 +227,6 @@ void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, Mixer if (field) { field->setDouble(value, elementName); - //mixer->updated(); } } } From 6ba8f3ca9e07c2d417977cdd326c972985377117 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 14:01:33 -0500 Subject: [PATCH 18/52] Fix from hyper to catch when multiple object requests stack up --- ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp index ba65e84e5..d8f98be5c 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/telemetry.cpp @@ -388,6 +388,11 @@ void Telemetry::processObjectQueue() UAVObject::UpdateMode updateMode = UAVObject::GetGcsTelemetryUpdateMode(metadata); if ( ( objInfo.event != EV_UNPACKED ) && ( ( objInfo.event != EV_UPDATED_PERIODIC ) || ( updateMode != UAVObject::UPDATEMODE_THROTTLED ) ) ) { + QMap::iterator itr = transMap.find(objInfo.obj->getObjID()); + if ( itr != transMap.end() ) { + qDebug() << "!!!!!! Making request for an object: " << objInfo.obj->getName() << " for which a request is already in progress!!!!!!"; + return; + } UAVObject::Metadata metadata = objInfo.obj->getMetadata(); ObjectTransactionInfo *transInfo = new ObjectTransactionInfo(this); transInfo->obj = objInfo.obj; From 9d82538a096528463a21874ecb150d7106169529 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 14:16:13 -0500 Subject: [PATCH 19/52] If we set FirmwareIAPObj to update on change then initial object retrieval will force it to be fetched before emitting the autopilotConnected signal. --- .../src/plugins/uavobjectutil/uavobjectutilmanager.cpp | 8 -------- shared/uavobjectdefinition/firmwareiapobj.xml | 2 +- 2 files changed, 1 insertion(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp index a30172fb0..be81befb7 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp @@ -247,14 +247,6 @@ FirmwareIAPObj::DataFields UAVObjectUtilManager::getFirmwareIap() if (!firmwareIap) return dummy; - // The code below will ask for the object update and wait for the updated to be received, - // or the timeout of the timer, set to 1 second. - QEventLoop loop; - connect(firmwareIap, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit())); - QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout - firmwareIap->requestUpdate(); - loop.exec(); - return firmwareIap->getData(); } diff --git a/shared/uavobjectdefinition/firmwareiapobj.xml b/shared/uavobjectdefinition/firmwareiapobj.xml index 30b070857..be8431ef5 100644 --- a/shared/uavobjectdefinition/firmwareiapobj.xml +++ b/shared/uavobjectdefinition/firmwareiapobj.xml @@ -10,7 +10,7 @@ - + From f5af60af3ea72e3b599035b30904d528f80d1807 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 27 Jul 2012 17:43:47 -0500 Subject: [PATCH 20/52] Increase the stack size for the system module now the saving occurs within that thread. --- flight/CopterControl/System/inc/pios_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/CopterControl/System/inc/pios_config.h b/flight/CopterControl/System/inc/pios_config.h index e4b70e931..dc3b10026 100644 --- a/flight/CopterControl/System/inc/pios_config.h +++ b/flight/CopterControl/System/inc/pios_config.h @@ -94,7 +94,7 @@ /* Task stack sizes */ #define PIOS_ACTUATOR_STACK_SIZE 1020 #define PIOS_MANUAL_STACK_SIZE 724 -#define PIOS_SYSTEM_STACK_SIZE 460 +#define PIOS_SYSTEM_STACK_SIZE 660 #define PIOS_STABILIZATION_STACK_SIZE 524 #define PIOS_TELEM_STACK_SIZE 500 #define PIOS_EVENTDISPATCHER_STACK_SIZE 130 From fc51680e6c1cc3982263d975c02382d84190a957 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 29 Jul 2012 23:08:59 +0300 Subject: [PATCH 21/52] Windows packaging: fix MinGW DLL locations for Qt 4.8.1+ (4.8.0 compatible) --- ground/openpilotgcs/copydata.pro | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/copydata.pro b/ground/openpilotgcs/copydata.pro index 7e1d5b1b5..d31730d80 100644 --- a/ground/openpilotgcs/copydata.pro +++ b/ground/openpilotgcs/copydata.pro @@ -9,9 +9,7 @@ equals(copydata, 1) { win32:CONFIG(release, debug|release) { # copy Qt DLLs and phonon4 - QT_DLLS = libgcc_s_dw2-1.dll \ - mingwm10.dll \ - phonon4.dll \ + QT_DLLS = phonon4.dll \ QtCore4.dll \ QtGui4.dll \ QtNetwork4.dll \ @@ -27,6 +25,13 @@ equals(copydata, 1) { data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() } + # copy MinGW DLLs + MINGW_DLLS = libgcc_s_dw2-1.dll \ + mingwm10.dll + for(dll, MINGW_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/../../../../../mingw/bin/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() + } + # copy iconengines QT_ICONENGINE_DLLS = qsvgicon4.dll data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/iconengines\") $$addNewline() From 08034df50ee0eabcecf645d84c7bda9afe116a85 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 29 Jul 2012 23:55:51 +0300 Subject: [PATCH 22/52] Windows packaging: update sh.cmd script for QtSDK 1.2.1 --- make/winx86/README.txt | 6 +++--- make/winx86/cmd/sh.cmd | 8 ++------ 2 files changed, 5 insertions(+), 9 deletions(-) diff --git a/make/winx86/README.txt b/make/winx86/README.txt index 17477d098..3bc070ee1 100644 --- a/make/winx86/README.txt +++ b/make/winx86/README.txt @@ -33,7 +33,7 @@ It is expected that you have the following tools installed into the listed locations (but any other locations are fine as well): - Python in C:\Python27 - - QtSDK in C:\Qt\2010.05 or C:\QtSDK (depending on SDK version) + - QtSDK in C:\QtSDK (depending on SDK version) - CodeSourcery G++ in %ProgramFiles%\CodeSourcery\Sourcery G++ Lite - msysGit in %ProgramFiles%\Git - Unicode NSIS in %ProgramFiles%\NSIS\Unicode @@ -190,8 +190,8 @@ This set of scripts uses the MSYS package included into the msysGit distribution and MinGW make included into the QtSDK package. The sh.cmd, shell_script.reg and this README.txt files were written -by Oleg Semyonov (os-openpilot-org@os-propo.info) for the OpenPilot -project and are licensed under CC-BY-SA terms: +by Oleg Semyonov (os@openpilot.org) for the OpenPilot project and +are licensed under CC-BY-SA terms: http://creativecommons.org/licenses/by-sa/3.0/ diff --git a/make/winx86/cmd/sh.cmd b/make/winx86/cmd/sh.cmd index 480044ab7..d9e74033b 100644 --- a/make/winx86/cmd/sh.cmd +++ b/make/winx86/cmd/sh.cmd @@ -54,12 +54,8 @@ set NOT_FOUND= set PATH_DIRS= call :which MSYSGIT "%ProgramFiles%\Git\bin" git.exe -rem These two lines for qt-sdk-win-opensource-2010.05.exe: -call :which QTMINGW "C:\Qt\2010.05\mingw\bin" mingw32-make.exe -call :which QTSDK "C:\Qt\2010.05\qt\bin" qmake.exe -rem These two lines for Qt_SDK_Win_offline_v1_1_1_en.exe: -rem call :which QTMINGW "C:\QtSDK\mingw\bin" mingw32-make.exe -rem call :which QTSDK "C:\QtSDK\Desktop\Qt\4.7.3\mingw\bin" qmake.exe +call :which QTMINGW "C:\QtSDK\mingw\bin" mingw32-make.exe +call :which QTSDK "C:\QtSDK\Desktop\Qt\4.8.1\mingw\bin" qmake.exe call :which CODESOURCERY "%ProgramFiles%\CodeSourcery\Sourcery G++ Lite\bin" cs-make.exe call :which PYTHON "C:\Python27" python.exe call :which UNSIS "%ProgramFiles%\NSIS\Unicode" makensis.exe From e75a2718f1e90aaaca81f3d490f4a7023469a05a Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 29 Jul 2012 23:08:59 +0300 Subject: [PATCH 23/52] Windows packaging: fix MinGW DLL locations for Qt 4.8.1+ (4.8.0 compatible) --- ground/openpilotgcs/copydata.pro | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/copydata.pro b/ground/openpilotgcs/copydata.pro index 7e1d5b1b5..d31730d80 100644 --- a/ground/openpilotgcs/copydata.pro +++ b/ground/openpilotgcs/copydata.pro @@ -9,9 +9,7 @@ equals(copydata, 1) { win32:CONFIG(release, debug|release) { # copy Qt DLLs and phonon4 - QT_DLLS = libgcc_s_dw2-1.dll \ - mingwm10.dll \ - phonon4.dll \ + QT_DLLS = phonon4.dll \ QtCore4.dll \ QtGui4.dll \ QtNetwork4.dll \ @@ -27,6 +25,13 @@ equals(copydata, 1) { data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() } + # copy MinGW DLLs + MINGW_DLLS = libgcc_s_dw2-1.dll \ + mingwm10.dll + for(dll, MINGW_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/../../../../../mingw/bin/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() + } + # copy iconengines QT_ICONENGINE_DLLS = qsvgicon4.dll data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/iconengines\") $$addNewline() From 1273a58d9f1a7f6aa7c08b1d9be8996163add3db Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 29 Jul 2012 23:55:51 +0300 Subject: [PATCH 24/52] Windows packaging: update sh.cmd script for QtSDK 1.2.1 --- make/winx86/README.txt | 6 +++--- make/winx86/cmd/sh.cmd | 8 ++------ 2 files changed, 5 insertions(+), 9 deletions(-) diff --git a/make/winx86/README.txt b/make/winx86/README.txt index 17477d098..3bc070ee1 100644 --- a/make/winx86/README.txt +++ b/make/winx86/README.txt @@ -33,7 +33,7 @@ It is expected that you have the following tools installed into the listed locations (but any other locations are fine as well): - Python in C:\Python27 - - QtSDK in C:\Qt\2010.05 or C:\QtSDK (depending on SDK version) + - QtSDK in C:\QtSDK (depending on SDK version) - CodeSourcery G++ in %ProgramFiles%\CodeSourcery\Sourcery G++ Lite - msysGit in %ProgramFiles%\Git - Unicode NSIS in %ProgramFiles%\NSIS\Unicode @@ -190,8 +190,8 @@ This set of scripts uses the MSYS package included into the msysGit distribution and MinGW make included into the QtSDK package. The sh.cmd, shell_script.reg and this README.txt files were written -by Oleg Semyonov (os-openpilot-org@os-propo.info) for the OpenPilot -project and are licensed under CC-BY-SA terms: +by Oleg Semyonov (os@openpilot.org) for the OpenPilot project and +are licensed under CC-BY-SA terms: http://creativecommons.org/licenses/by-sa/3.0/ diff --git a/make/winx86/cmd/sh.cmd b/make/winx86/cmd/sh.cmd index 480044ab7..d9e74033b 100644 --- a/make/winx86/cmd/sh.cmd +++ b/make/winx86/cmd/sh.cmd @@ -54,12 +54,8 @@ set NOT_FOUND= set PATH_DIRS= call :which MSYSGIT "%ProgramFiles%\Git\bin" git.exe -rem These two lines for qt-sdk-win-opensource-2010.05.exe: -call :which QTMINGW "C:\Qt\2010.05\mingw\bin" mingw32-make.exe -call :which QTSDK "C:\Qt\2010.05\qt\bin" qmake.exe -rem These two lines for Qt_SDK_Win_offline_v1_1_1_en.exe: -rem call :which QTMINGW "C:\QtSDK\mingw\bin" mingw32-make.exe -rem call :which QTSDK "C:\QtSDK\Desktop\Qt\4.7.3\mingw\bin" qmake.exe +call :which QTMINGW "C:\QtSDK\mingw\bin" mingw32-make.exe +call :which QTSDK "C:\QtSDK\Desktop\Qt\4.8.1\mingw\bin" qmake.exe call :which CODESOURCERY "%ProgramFiles%\CodeSourcery\Sourcery G++ Lite\bin" cs-make.exe call :which PYTHON "C:\Python27" python.exe call :which UNSIS "%ProgramFiles%\NSIS\Unicode" makensis.exe From dcf68c2359b67eb725c46ae72774d311e114d27b Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Mon, 30 Jul 2012 00:03:01 +0300 Subject: [PATCH 25/52] AeroSimRC: fix MinGW DLL locations for Qt 4.8.1+ (4.8.0 compatible) --- .../src/plugins/hitlv2/aerosimrc/src/plugin.pro | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro index b31d6881b..071559ef3 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro @@ -57,14 +57,20 @@ equals(copydata, 1) { # Qt DLLs QT_DLLS = \ - libgcc_s_dw2-1.dll \ - mingwm10.dll \ QtCore4.dll \ QtNetwork4.dll for(dll, QT_DLLS) { data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$SIM_DIR/$$dll\") $$addNewline() } + # MinGW DLLs + MINGW_DLLS = \ + libgcc_s_dw2-1.dll \ + mingwm10.dll + for(dll, MINGW_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/../../../../../mingw/bin/$$dll\") $$targetPath(\"$$SIM_DIR/$$dll\") $$addNewline() + } + data_copy.target = FORCE QMAKE_EXTRA_TARGETS += data_copy } From 51b7e1116049f55182a1fff0721df55a54439a45 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Mon, 30 Jul 2012 00:08:43 +0300 Subject: [PATCH 26/52] AeroSimRC: remove unused MSVC options --- .../plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h | 9 --------- .../src/plugins/hitlv2/aerosimrc/src/plugin.pro | 6 ------ .../src/plugins/hitlv2/aerosimrc/src/udptestwidget.h | 3 --- 3 files changed, 18 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h index 4adf7c16e..697695bc2 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h @@ -38,13 +38,7 @@ const quint16 DBG_BUFFER_MAX_SIZE = 4096; #define OBSOLETE_MIT_CHECKBOX (1 << 1) #define OBSOLETE_MIT_SEPARATOR (1 << 7) -#if defined(Q_CC_MSVC) -#define PACK_STRUCT -#define MAX_PATH 260 -#pragma pack (push, r1, 1) -#elif defined(Q_CC_GNU) #define PACK_STRUCT __attribute__((packed)) -#endif struct simToPlugin { @@ -207,9 +201,6 @@ struct pluginInit const char *strOutputFolder; } PACK_STRUCT ; // normal - 144, packed - 144 OK (3.81 & 3.83 & 3.90) -#ifdef Q_CC_MSVC -#pragma pack (pop, r1) -#endif #undef PACK_STRUCT #endif // AEROSIMRCDATASTRUCT_H diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro index 071559ef3..51bb42abd 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro @@ -15,12 +15,6 @@ SIM_DIR = $$GCS_BUILD_TREE/../AeroSIM-RC PLUGIN_DIR = $$SIM_DIR/Plugin/CopterControl DLLDESTDIR = $$PLUGIN_DIR -# Don't depend on MSVRT*.dll -win32-msvc* { - QMAKE_CXXFLAGS_RELEASE -= -MD - QMAKE_CXXFLAGS_MT_DLL += -MT -} - HEADERS = \ aerosimrcdatastruct.h \ enums.h \ diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h index eeca63555..500f35482 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h +++ b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h @@ -31,9 +31,6 @@ #include #include #include -#if defined(Q_CC_MSVC) -#define _USE_MATH_DEFINES -#endif #include #include #include From b8450d4a073756da5784193776c9fb6ee9475468 Mon Sep 17 00:00:00 2001 From: Werner Backes Date: Tue, 31 Jul 2012 00:18:10 +0200 Subject: [PATCH 27/52] Fixed World Magnetic Model to accept altitude in meters instead of kilometers --- flight/Libraries/WorldMagModel.c | 2 +- ground/openpilotgcs/src/libs/utils/worldmagmodel.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Libraries/WorldMagModel.c b/flight/Libraries/WorldMagModel.c index cae0ec106..83f413200 100644 --- a/flight/Libraries/WorldMagModel.c +++ b/flight/Libraries/WorldMagModel.c @@ -242,7 +242,7 @@ int WMM_GetMagVector(float Lat, float Lon, float AltEllipsoid, uint16_t Month, u { CoordGeodetic->lambda = Lon; CoordGeodetic->phi = Lat; - CoordGeodetic->HeightAboveEllipsoid = AltEllipsoid; + CoordGeodetic->HeightAboveEllipsoid = AltEllipsoid/1000.0; // convert to km // Convert from geodeitic to Spherical Equations: 17-18, WMM Technical report if (WMM_GeodeticToSpherical(CoordGeodetic, CoordSpherical) < 0) diff --git a/ground/openpilotgcs/src/libs/utils/worldmagmodel.cpp b/ground/openpilotgcs/src/libs/utils/worldmagmodel.cpp index ce8201ece..207d4b051 100644 --- a/ground/openpilotgcs/src/libs/utils/worldmagmodel.cpp +++ b/ground/openpilotgcs/src/libs/utils/worldmagmodel.cpp @@ -158,7 +158,7 @@ namespace Utils { { double Lat = LLA[0]; double Lon = LLA[1]; - double AltEllipsoid = LLA[2]; + double AltEllipsoid = LLA[2]/1000.0; // convert to km // *********** // range check supplied params From 56647f5409a9f7e47be205eb5fabafda239c49cf Mon Sep 17 00:00:00 2001 From: "Richard Flay (Hyper)" Date: Tue, 31 Jul 2012 11:07:07 +0930 Subject: [PATCH 28/52] Fix for OP-661: error messages in GCS log due to obsolete AHRSComms and SDCard related alarms. Change also disables obsolete SDCard support on the flight side of CC and PipX --- flight/CopterControl/System/inc/pios_config_posix.h | 1 - flight/PipXtreme/System/inc/pios_config_posix.h | 1 - flight/SimPosix/System/inc/pios_config.h | 1 - flight/UAVObjects/inc/uavobjectmanager.h | 9 ++------- flight/UAVObjects/uavobjectmanager.c | 10 ++++------ shared/uavobjectdefinition/systemalarms.xml | 2 +- 6 files changed, 7 insertions(+), 17 deletions(-) diff --git a/flight/CopterControl/System/inc/pios_config_posix.h b/flight/CopterControl/System/inc/pios_config_posix.h index f7dd4aa2e..ed2351ea6 100644 --- a/flight/CopterControl/System/inc/pios_config_posix.h +++ b/flight/CopterControl/System/inc/pios_config_posix.h @@ -33,7 +33,6 @@ #define PIOS_INCLUDE_SYS #define PIOS_INCLUDE_DELAY #define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SDCARD #define PIOS_INCLUDE_FREERTOS #define PIOS_INCLUDE_COM #define PIOS_INCLUDE_UDP diff --git a/flight/PipXtreme/System/inc/pios_config_posix.h b/flight/PipXtreme/System/inc/pios_config_posix.h index ddf7ee5d4..9d589d634 100755 --- a/flight/PipXtreme/System/inc/pios_config_posix.h +++ b/flight/PipXtreme/System/inc/pios_config_posix.h @@ -33,7 +33,6 @@ #define PIOS_INCLUDE_SYS #define PIOS_INCLUDE_DELAY #define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SDCARD #define PIOS_INCLUDE_FREERTOS #define PIOS_INCLUDE_COM #define PIOS_INCLUDE_UDP diff --git a/flight/SimPosix/System/inc/pios_config.h b/flight/SimPosix/System/inc/pios_config.h index d4add3666..84d857f19 100644 --- a/flight/SimPosix/System/inc/pios_config.h +++ b/flight/SimPosix/System/inc/pios_config.h @@ -44,7 +44,6 @@ //#define PIOS_INCLUDE_I2C #define PIOS_INCLUDE_IRQ #define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SDCARD //#define PIOS_INCLUDE_IAP #define PIOS_INCLUDE_SERVO #define PIOS_INCLUDE_SPI diff --git a/flight/UAVObjects/inc/uavobjectmanager.h b/flight/UAVObjects/inc/uavobjectmanager.h index 62aff543d..7d774d5ae 100644 --- a/flight/UAVObjects/inc/uavobjectmanager.h +++ b/flight/UAVObjects/inc/uavobjectmanager.h @@ -46,13 +46,6 @@ #define UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT 6 #define UAVOBJ_UPDATE_MODE_MASK 0x3 - -// FIXME: All this typedef for SDCARD needs to be abstracted away -#if !defined(PIOS_INCLUDE_SDCARD) -typedef struct {} FILEINFO; -#endif - - typedef void* UAVObjHandle; /** @@ -164,8 +157,10 @@ int32_t UAVObjPack(UAVObjHandle obj_handle, uint16_t instId, uint8_t* dataOut); int32_t UAVObjSave(UAVObjHandle obj_handle, uint16_t instId); int32_t UAVObjLoad(UAVObjHandle obj_handle, uint16_t instId); int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId); +#if defined(PIOS_INCLUDE_SDCARD) int32_t UAVObjSaveToFile(UAVObjHandle obj_handle, uint16_t instId, FILEINFO* file); UAVObjHandle UAVObjLoadFromFile(FILEINFO* file); +#endif int32_t UAVObjSaveSettings(); int32_t UAVObjLoadSettings(); int32_t UAVObjDeleteSettings(); diff --git a/flight/UAVObjects/uavobjectmanager.c b/flight/UAVObjects/uavobjectmanager.c index 2b2b69018..c339af0fe 100644 --- a/flight/UAVObjects/uavobjectmanager.c +++ b/flight/UAVObjects/uavobjectmanager.c @@ -668,6 +668,7 @@ unlock_exit: return rc; } +#if defined(PIOS_INCLUDE_SDCARD) /** * Save the data of the specified object instance to the file system (SD card). * The object will be appended and the file will not be closed. @@ -682,7 +683,6 @@ int32_t UAVObjSaveToFile(UAVObjHandle obj_handle, uint16_t instId, { PIOS_Assert(obj_handle); -#if defined(PIOS_INCLUDE_SDCARD) uint32_t bytesWritten; // Check for file system availability if (PIOS_SDCARD_IsMounted() == 0) { @@ -741,9 +741,9 @@ int32_t UAVObjSaveToFile(UAVObjHandle obj_handle, uint16_t instId, } // Done xSemaphoreGiveRecursive(mutex); -#endif /* PIOS_INCLUDE_SDCARD */ return 0; } +#endif /* PIOS_INCLUDE_SDCARD */ /** * Save the data of the specified object to the file system (SD card). @@ -811,6 +811,7 @@ int32_t UAVObjSave(UAVObjHandle obj_handle, uint16_t instId) return 0; } +#if defined(PIOS_INCLUDE_SDCARD) /** * Load an object from the file system (SD card). * @param[in] file File to read from @@ -818,7 +819,6 @@ int32_t UAVObjSave(UAVObjHandle obj_handle, uint16_t instId) */ UAVObjHandle UAVObjLoadFromFile(FILEINFO * file) { -#if defined(PIOS_INCLUDE_SDCARD) uint32_t bytesRead; struct UAVOBase *objEntry; InstanceHandle instEntry; @@ -898,10 +898,8 @@ UAVObjHandle UAVObjLoadFromFile(FILEINFO * file) // Unlock xSemaphoreGiveRecursive(mutex); return obj_handle; -#else /* PIOS_INCLUDE_SDCARD */ - return NULL; -#endif } +#endif /* PIOS_INCLUDE_SDCARD */ /** * Load an object from the file system (SD card). diff --git a/shared/uavobjectdefinition/systemalarms.xml b/shared/uavobjectdefinition/systemalarms.xml index cc20045b6..dd185cfa3 100644 --- a/shared/uavobjectdefinition/systemalarms.xml +++ b/shared/uavobjectdefinition/systemalarms.xml @@ -2,7 +2,7 @@ Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + elementnames="OutOfMemory,StackOverflow,CPUOverload,EventSystem,Telemetry,ManualControl,Actuator,Attitude,Sensors,Stabilization,Guidance,Battery,FlightTime,I2C,GPS,BootFault" defaultvalue="Uninitialised"/> From e32152386a7dfd242f39cebf603eb36c361ddd2d Mon Sep 17 00:00:00 2001 From: Werner Backes Date: Tue, 31 Jul 2012 11:10:23 +0200 Subject: [PATCH 29/52] Increased stack for PIOS_SETS_HOMELOCATION case to avoid running into low stack warnings when settings the home location from GPS was actually used. --- flight/Modules/GPS/GPS.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index 5851ac10d..0428cb629 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -66,7 +66,7 @@ static float GravityAccel(float latitude, float longitude, float altitude); #ifdef PIOS_GPS_SETS_HOMELOCATION // Unfortunately need a good size stack for the WMM calculation - #define STACK_SIZE_BYTES 750 + #define STACK_SIZE_BYTES 784 #else #if defined(PIOS_GPS_MINIMAL) #define STACK_SIZE_BYTES 500 From 4d257860c8ccd358b9c773f5780f8007121bdd48 Mon Sep 17 00:00:00 2001 From: Ryan Hunter Date: Wed, 18 Jul 2012 17:08:22 -0400 Subject: [PATCH 30/52] Moved the matlab files to matlab folder for GCS plugin --- .../plugins/gcscontrol/Matlab => matlab/GCSPlugin}/GCSControl.m | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename {ground/openpilotgcs/src/plugins/gcscontrol/Matlab => matlab/GCSPlugin}/GCSControl.m (100%) diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/Matlab/GCSControl.m b/matlab/GCSPlugin/GCSControl.m similarity index 100% rename from ground/openpilotgcs/src/plugins/gcscontrol/Matlab/GCSControl.m rename to matlab/GCSPlugin/GCSControl.m From 6d347954941e718c374c10402f1f86c5072e0683 Mon Sep 17 00:00:00 2001 From: "Richard Flay (Hyper)" Date: Wed, 1 Aug 2012 19:53:59 +0930 Subject: [PATCH 31/52] Re-enabled simposix SDCard support, and removed obsolete SDCard alarm usage from System module --- flight/Modules/System/systemmod.c | 9 --------- flight/SimPosix/System/inc/pios_config.h | 1 + .../diagrams/default/system-health.svg | 20 ------------------- 3 files changed, 1 insertion(+), 29 deletions(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 33bf462fb..715c26d72 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -463,15 +463,6 @@ static void updateSystemAlarms() AlarmsClear(SYSTEMALARMS_ALARM_STACKOVERFLOW); } -#if defined(PIOS_INCLUDE_SDCARD) - // Check for SD card - if (PIOS_SDCARD_IsMounted() == 0) { - AlarmsSet(SYSTEMALARMS_ALARM_SDCARD, SYSTEMALARMS_ALARM_ERROR); - } else { - AlarmsClear(SYSTEMALARMS_ALARM_SDCARD); - } -#endif - // Check for event errors UAVObjGetStats(&objStats); EventGetStats(&evStats); diff --git a/flight/SimPosix/System/inc/pios_config.h b/flight/SimPosix/System/inc/pios_config.h index 84d857f19..d4add3666 100644 --- a/flight/SimPosix/System/inc/pios_config.h +++ b/flight/SimPosix/System/inc/pios_config.h @@ -44,6 +44,7 @@ //#define PIOS_INCLUDE_I2C #define PIOS_INCLUDE_IRQ #define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_SDCARD //#define PIOS_INCLUDE_IAP #define PIOS_INCLUDE_SERVO #define PIOS_INCLUDE_SPI diff --git a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg index 2ec58bd37..fb82a980c 100644 --- a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg +++ b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg @@ -1385,26 +1385,6 @@ id="Telemetry-Critical" style="fill:#cf0e0e;fill-opacity:1;stroke:#ffffff;stroke-width:0.29055119;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" /> - - - - Date: Wed, 1 Aug 2012 14:42:21 +0100 Subject: [PATCH 32/52] GCS-Made the UI limits board specific --- .../src/plugins/config/configinputwidget.cpp | 12 +++---- .../src/plugins/uavobjects/uavobjectfield.cpp | 28 +++++++++++++--- .../src/plugins/uavobjects/uavobjectfield.h | 7 ++-- .../uavobjectwidgetutils/configtaskwidget.cpp | 33 +++++++++++-------- .../uavobjectwidgetutils/configtaskwidget.h | 2 ++ .../manualcontrolsettings.xml | 2 +- 6 files changed, 56 insertions(+), 28 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index 7952b3d70..e0425d963 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -82,12 +82,12 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent) connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack())); m_config->stackedWidget->setCurrentIndex(0); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,3); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,4); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0,1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1,1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2,1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,3,1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,4,1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5,1,true); addUAVObjectToWidgetRelation("ManualControlSettings","FlightModeNumber",m_config->fmsPosNum); addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll"); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp index 5ccd7371f..71e4b27a6 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp @@ -113,12 +113,22 @@ void UAVObjectField::limitsInitialize(const QString &limits) quint32 index=0; foreach (QString str, stringPerElement) { QString _str=str.trimmed(); + if(_str.isEmpty()) + continue; QStringList valuesPerElement=_str.split(":"); LimitStruct lstruc; bool b1=valuesPerElement.at(0).startsWith("%"); bool b2=(int)(index)<(int)numElements; - if(b1 && b2) + bool b3=valuesPerElement.at(0).size()==3; + bool auxb; + valuesPerElement.at(0).mid(1,4).toInt(&auxb,16); + bool b4=((valuesPerElement.at(0).size())==7 && auxb); + if(b1 && b2 && (b3 || b4)) { + if(b4) + lstruc.board=valuesPerElement.at(0).mid(1,4).toInt(&auxb,16); + else + lstruc.board=0; if(valuesPerElement.at(0).right(2)=="EQ") lstruc.type=EQUAL; else if(valuesPerElement.at(0).right(2)=="NE") @@ -140,7 +150,7 @@ void UAVObjectField::limitsInitialize(const QString &limits) case UINT8: case UINT16: case UINT32: - case BITFIELD: + case BITFIELD: lstruc.values.append((quint32)value.toULong()); break; case INT8: @@ -170,14 +180,18 @@ void UAVObjectField::limitsInitialize(const QString &limits) qDebug()<<"limits parsing failed (property doesn't start with %) on UAVObjectField"<numelements) on UAVObjectField"< values; + int board; } LimitStruct; UAVObjectField(const QString& name, const QString& units, FieldType type, quint32 numElements, const QStringList& options,const QString& limits=QString()); @@ -74,9 +75,9 @@ public: bool isText(); QString toString(); - bool isWithinLimits(QVariant var, quint32 index); - QVariant getMaxLimit(quint32 index); - QVariant getMinLimit(quint32 index); + bool isWithinLimits(QVariant var, quint32 index, int board=0); + QVariant getMaxLimit(quint32 index, int board=0); + QVariant getMinLimit(quint32 index, int board=0); signals: void fieldUpdated(UAVObjectField* field); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 7fb8d70c7..594063358 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -37,6 +37,7 @@ ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnecte pm = ExtensionSystem::PluginManager::instance(); objManager = pm->getObject(); TelemetryManager* telMngr = pm->getObject(); + utilMngr = pm->getObject(); connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect())); connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect())); connect(telMngr, SIGNAL(connected()), this, SIGNAL(autoPilotConnected())); @@ -226,9 +227,15 @@ void ConfigTaskWidget::onAutopilotDisconnect() void ConfigTaskWidget::onAutopilotConnect() { + if (utilMngr) + currentBoard = utilMngr->getBoardModel();//TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE invalidateObjects(); dirty=false; isConnected=true; + foreach(objectToWidget * ow,objOfInterest) + { + loadWidgetLimits(ow->widget,ow->field,ow->index,ow->isLimited,ow->scale); + } enableControls(true); refreshWidgetsValues(); } @@ -1057,7 +1064,7 @@ void ConfigTaskWidget::checkWidgetsLimits(QWidget * widget,UAVObjectField * fiel { if(!hasLimits) return; - if(!field->isWithinLimits(value,index)) + if(!field->isWithinLimits(value,index,currentBoard)) { if(!widget->property("styleBackup").isValid()) widget->setProperty("styleBackup",widget->styleSheet()); @@ -1131,7 +1138,7 @@ void ConfigTaskWidget::loadWidgetLimits(QWidget * widget,UAVObjectField * field, { foreach(QString str,option) { - if(field->isWithinLimits(str,index)) + if(field->isWithinLimits(str,index,currentBoard)) cb->addItem(str); } } @@ -1144,33 +1151,33 @@ void ConfigTaskWidget::loadWidgetLimits(QWidget * widget,UAVObjectField * field, { if(field->getMaxLimit(index).isValid()) { - cb->setMaximum((double)(field->getMaxLimit(index).toDouble()/scale)); + cb->setMaximum((double)(field->getMaxLimit(index,currentBoard).toDouble()/scale)); } - if(field->getMinLimit(index).isValid()) + if(field->getMinLimit(index,currentBoard).isValid()) { - cb->setMinimum((double)(field->getMinLimit(index).toDouble()/scale)); + cb->setMinimum((double)(field->getMinLimit(index,currentBoard).toDouble()/scale)); } } else if(QSpinBox * cb=qobject_cast(widget)) { - if(field->getMaxLimit(index).isValid()) + if(field->getMaxLimit(index,currentBoard).isValid()) { - cb->setMaximum((int)qRound(field->getMaxLimit(index).toDouble()/scale)); + cb->setMaximum((int)qRound(field->getMaxLimit(index,currentBoard).toDouble()/scale)); } - if(field->getMinLimit(index).isValid()) + if(field->getMinLimit(index,currentBoard).isValid()) { - cb->setMinimum((int)qRound(field->getMinLimit(index).toDouble()/scale)); + cb->setMinimum((int)qRound(field->getMinLimit(index,currentBoard).toDouble()/scale)); } } else if(QSlider * cb=qobject_cast(widget)) { - if(field->getMaxLimit(index).isValid()) + if(field->getMaxLimit(index,currentBoard).isValid()) { - cb->setMaximum((int)qRound(field->getMaxLimit(index).toDouble()/scale)); + cb->setMaximum((int)qRound(field->getMaxLimit(index,currentBoard).toDouble()/scale)); } - if(field->getMinLimit(index).isValid()) + if(field->getMinLimit(index,currentBoard).isValid()) { - cb->setMinimum((int)(field->getMinLimit(index).toDouble()/scale)); + cb->setMinimum((int)(field->getMinLimit(index,currentBoard).toDouble()/scale)); } } } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index 3cac0abc0..0a17aa544 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -144,12 +144,14 @@ private slots: void defaultButtonClicked(); void reloadButtonClicked(); private: + int currentBoard; bool isConnected; bool allowWidgetUpdates; QStringList objectsList; QList objOfInterest; ExtensionSystem::PluginManager *pm; UAVObjectManager *objManager; + UAVObjectUtilManager* utilMngr; smartSaveButton *smartsave; QMap objectUpdates; QMap *> defaultReloadGroups; diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index 09d4ca618..87924a065 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -24,7 +24,7 @@ - + From cb26100d65f1c95beeeaed22d7afc31d4def0660 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 2 Aug 2012 16:48:37 +0100 Subject: [PATCH 33/52] GCS - Dummy commit to see if crucible notices this branch --- .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 594063358..b08fea191 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -230,6 +230,7 @@ void ConfigTaskWidget::onAutopilotConnect() if (utilMngr) currentBoard = utilMngr->getBoardModel();//TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE invalidateObjects(); + dirty=false; isConnected=true; foreach(objectToWidget * ow,objOfInterest) From 352f18bec0597d90cb7b3dcad2bf0f7530ac63fc Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 2 Aug 2012 23:56:02 +0100 Subject: [PATCH 34/52] GCS-Allow for more than 1 limit per index --- .../src/plugins/uavobjects/uavobjectfield.cpp | 613 +++++++++--------- .../src/plugins/uavobjects/uavobjectfield.h | 2 +- 2 files changed, 320 insertions(+), 295 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp index 71e4b27a6..fcd108155 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp @@ -112,76 +112,94 @@ void UAVObjectField::limitsInitialize(const QString &limits) QStringList stringPerElement=limits.split(","); quint32 index=0; foreach (QString str, stringPerElement) { - QString _str=str.trimmed(); - if(_str.isEmpty()) - continue; - QStringList valuesPerElement=_str.split(":"); - LimitStruct lstruc; - bool b1=valuesPerElement.at(0).startsWith("%"); - bool b2=(int)(index)<(int)numElements; - bool b3=valuesPerElement.at(0).size()==3; - bool auxb; - valuesPerElement.at(0).mid(1,4).toInt(&auxb,16); - bool b4=((valuesPerElement.at(0).size())==7 && auxb); - if(b1 && b2 && (b3 || b4)) + QStringList ruleList=str.split(";"); + QList limitList; + foreach(QString rule,ruleList) { - if(b4) - lstruc.board=valuesPerElement.at(0).mid(1,4).toInt(&auxb,16); - else - lstruc.board=0; - if(valuesPerElement.at(0).right(2)=="EQ") - lstruc.type=EQUAL; - else if(valuesPerElement.at(0).right(2)=="NE") - lstruc.type=NOT_EQUAL; - else if(valuesPerElement.at(0).right(2)=="BE") - lstruc.type=BETWEEN; - else if(valuesPerElement.at(0).right(2)=="BI") - lstruc.type=BIGGER; - else if(valuesPerElement.at(0).right(2)=="SM") - lstruc.type=SMALLER; - else - qDebug()<<"limits parsing failed (invalid property) on UAVObjectField"<numelements) on UAVObjectField"< limitList,elementLimits) + { + foreach(LimitStruct limit,limitList) { - if(!valuesPerElement.at(0).isEmpty() && !b1) - qDebug()<<"limits parsing failed (property doesn't start with %) on UAVObjectField"<numelements) on UAVObjectField"<2) + qDebug()<<__FUNCTION__<<"between limit with more than 1 pair, using first; field"<=struc.values.at(0).toInt() && var.toInt()<=struc.values.at(1).toInt())) + return false; + return true; + break; + case UINT8: + case UINT16: + case UINT32: + case BITFIELD: + if(!(var.toUInt()>=struc.values.at(0).toUInt() && var.toUInt()<=struc.values.at(1).toUInt())) + return false; + return true; + break; + case ENUM: + if(!(options.indexOf(var.toString())>=options.indexOf(struc.values.at(0).toString()) && options.indexOf(var.toString())<=options.indexOf(struc.values.at(1).toString()))) + return false; + return true; + break; + case STRING: + return true; + break; + case FLOAT32: + if(!(var.toFloat()>=struc.values.at(0).toFloat() && var.toFloat()<=struc.values.at(1).toFloat())) + return false; + return true; + break; + default: + return true; } - return false; break; - default: - return true; - } - break; - case NOT_EQUAL: - switch (type) - { - case INT8: - case INT16: - case INT32: - foreach (QVariant vars, struc.values) { - if(var.toInt()==vars.toInt()) - return false; + case BIGGER: + if(struc.values.length()<1) + { + qDebug()<<__FUNCTION__<<"BIGGER limit with less than 1 value, aborting; field:"<1) + qDebug()<<__FUNCTION__<<"BIGGER limit with more than 1 value, using first; field"<=struc.values.at(0).toInt())) + return false; + return true; + break; + case UINT8: + case UINT16: + case UINT32: + case BITFIELD: + if(!(var.toUInt()>=struc.values.at(0).toUInt())) + return false; + return true; + break; + case ENUM: + if(!(options.indexOf(var.toString())>=options.indexOf(struc.values.at(0).toString()))) + return false; + return true; + break; + case STRING: + return true; + break; + case FLOAT32: + if(!(var.toFloat()>=struc.values.at(0).toFloat())) + return false; + return true; + break; + default: + return true; } - return true; break; - case ENUM: - case STRING: - foreach (QVariant vars, struc.values) { - if(var.toString()==vars.toString()) - return false; + case SMALLER: + switch (type) + { + case INT8: + case INT16: + case INT32: + if(!(var.toInt()<=struc.values.at(0).toInt())) + return false; + return true; + break; + case UINT8: + case UINT16: + case UINT32: + case BITFIELD: + if(!(var.toUInt()<=struc.values.at(0).toUInt())) + return false; + return true; + break; + case ENUM: + if(!(options.indexOf(var.toString())<=options.indexOf(struc.values.at(0).toString()))) + return false; + return true; + break; + case STRING: + return true; + break; + case FLOAT32: + if(!(var.toFloat()<=struc.values.at(0).toFloat())) + return false; + return true; + break; + default: + return true; } - return true; - break; - case FLOAT32: - foreach (QVariant vars, struc.values) { - if(var.toFloat()==vars.toFloat()) - return false; - } - return true; - break; - default: - return true; - } - break; - case BETWEEN: - if(struc.values.length()<2) - { - qDebug()<<__FUNCTION__<<"between limit with less than 1 pair, aborting; field:"<2) - qDebug()<<__FUNCTION__<<"between limit with more than 1 pair, using first; field"<=struc.values.at(0).toInt() && var.toInt()<=struc.values.at(1).toInt())) - return false; - return true; - break; - case UINT8: - case UINT16: - case UINT32: - case BITFIELD: - if(!(var.toUInt()>=struc.values.at(0).toUInt() && var.toUInt()<=struc.values.at(1).toUInt())) - return false; - return true; - break; - case ENUM: - if(!(options.indexOf(var.toString())>=options.indexOf(struc.values.at(0).toString()) && options.indexOf(var.toString())<=options.indexOf(struc.values.at(1).toString()))) - return false; - return true; - break; - case STRING: - return true; - break; - case FLOAT32: - if(!(var.toFloat()>=struc.values.at(0).toFloat() && var.toFloat()<=struc.values.at(1).toFloat())) - return false; - return true; - break; - default: - return true; - } - break; - case BIGGER: - if(struc.values.length()<1) - { - qDebug()<<__FUNCTION__<<"BIGGER limit with less than 1 value, aborting; field:"<1) - qDebug()<<__FUNCTION__<<"BIGGER limit with more than 1 value, using first; field"<=struc.values.at(0).toInt())) - return false; - return true; - break; - case UINT8: - case UINT16: - case UINT32: - case BITFIELD: - if(!(var.toUInt()>=struc.values.at(0).toUInt())) - return false; - return true; - break; - case ENUM: - if(!(options.indexOf(var.toString())>=options.indexOf(struc.values.at(0).toString()))) - return false; - return true; - break; - case STRING: - return true; - break; - case FLOAT32: - if(!(var.toFloat()>=struc.values.at(0).toFloat())) - return false; - return true; - break; - default: - return true; - } - break; - case SMALLER: - switch (type) - { - case INT8: - case INT16: - case INT32: - if(!(var.toInt()<=struc.values.at(0).toInt())) - return false; - return true; - break; - case UINT8: - case UINT16: - case UINT32: - case BITFIELD: - if(!(var.toUInt()<=struc.values.at(0).toUInt())) - return false; - return true; - break; - case ENUM: - if(!(options.indexOf(var.toString())<=options.indexOf(struc.values.at(0).toString()))) - return false; - return true; - break; - case STRING: - return true; - break; - case FLOAT32: - if(!(var.toFloat()<=struc.values.at(0).toFloat())) - return false; - return true; - break; - default: - return true; } } return true; @@ -402,55 +423,59 @@ QVariant UAVObjectField::getMaxLimit(quint32 index,int board) { if(!elementLimits.keys().contains(index)) return QVariant(); - LimitStruct struc=elementLimits.value(index); - if((struc.board!=board) && board!=0 && struc.board!=0) - return QVariant(); - switch(struc.type) + foreach(LimitStruct struc,elementLimits.value(index)) { - case EQUAL: - case NOT_EQUAL: - case BIGGER: - return QVariant(); - break; - break; - case BETWEEN: - return struc.values.at(1); - break; - case SMALLER: - return struc.values.at(0); - break; - default: - return QVariant(); - break; + if((struc.board!=board) && board!=0 && struc.board!=0) + continue; + switch(struc.type) + { + case EQUAL: + case NOT_EQUAL: + case BIGGER: + return QVariant(); + break; + break; + case BETWEEN: + return struc.values.at(1); + break; + case SMALLER: + return struc.values.at(0); + break; + default: + return QVariant(); + break; + } } - return QVariant(); + return QVariant(); } QVariant UAVObjectField::getMinLimit(quint32 index, int board) { if(!elementLimits.keys().contains(index)) return QVariant(); - LimitStruct struc=elementLimits.value(index); - if((struc.board!=board) && board!=0 && struc.board!=0) - return QVariant(); - switch(struc.type) + foreach(LimitStruct struc,elementLimits.value(index)) { - case EQUAL: - case NOT_EQUAL: - case SMALLER: - return QVariant(); - break; - break; - case BETWEEN: - return struc.values.at(0); - break; - case BIGGER: - return struc.values.at(0); - break; - default: - return QVariant(); - break; + if((struc.board!=board) && board!=0 && struc.board!=0) + return QVariant(); + switch(struc.type) + { + case EQUAL: + case NOT_EQUAL: + case SMALLER: + return QVariant(); + break; + break; + case BETWEEN: + return struc.values.at(0); + break; + case BIGGER: + return struc.values.at(0); + break; + default: + return QVariant(); + break; + } } - return QVariant(); + return QVariant(); } void UAVObjectField::initialize(quint8* data, quint32 dataOffset, UAVObject* obj) { diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h index d570efe6d..48d927797 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h @@ -92,7 +92,7 @@ protected: quint32 offset; quint8* data; UAVObject* obj; - QMap elementLimits; + QMap > elementLimits; void clear(); void constructorInitialize(const QString& name, const QString& units, FieldType type, const QStringList& elementNames, const QStringList& options, const QString &limits); void limitsInitialize(const QString &limits); From dafc455bfacda41f67f69912b6340ea8f1ae419a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 3 Aug 2012 09:36:59 -0500 Subject: [PATCH 35/52] Increase the manualcontrol stack size based on Stac's comments --- flight/CopterControl/System/inc/pios_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/CopterControl/System/inc/pios_config.h b/flight/CopterControl/System/inc/pios_config.h index dc3b10026..371276211 100644 --- a/flight/CopterControl/System/inc/pios_config.h +++ b/flight/CopterControl/System/inc/pios_config.h @@ -93,7 +93,7 @@ /* Task stack sizes */ #define PIOS_ACTUATOR_STACK_SIZE 1020 -#define PIOS_MANUAL_STACK_SIZE 724 +#define PIOS_MANUAL_STACK_SIZE 800 #define PIOS_SYSTEM_STACK_SIZE 660 #define PIOS_STABILIZATION_STACK_SIZE 524 #define PIOS_TELEM_STACK_SIZE 500 From df61d33f669851883a48eed618e83f1f9355a083 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 3 Aug 2012 18:57:24 +0100 Subject: [PATCH 36/52] GCS- Added the ability to have more than 1 ui limit per index --- .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 1 - shared/uavobjectdefinition/manualcontrolsettings.xml | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index b08fea191..594063358 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -230,7 +230,6 @@ void ConfigTaskWidget::onAutopilotConnect() if (utilMngr) currentBoard = utilMngr->getBoardModel();//TODO REMEMBER TO ADD THIS TO FORCE CONNECTED FUNC ON CC3D_RELEASE invalidateObjects(); - dirty=false; isConnected=true; foreach(objectToWidget * ow,objOfInterest) diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index 87924a065..d9c5af7a5 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -24,7 +24,7 @@ - + From ef0c12b1b6ca42159aaa76a9ab50964902c5459b Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sun, 5 Aug 2012 21:45:27 -0400 Subject: [PATCH 37/52] hid joystick: emulate a USB HID joystick using RC Transmitter Adds a new RCTransmitter setting for the USB HID interface which emulates a USB HID joystick. The scaled RC receiver channels from any RCVR protocol are passed through to the various emulated joystick controls. The main use for this feature is to allow you to use your own RC transmitter with any RC simulator on a PC. This is known to work with CRRCsim but should work with any simulator that supports joystick input. --- flight/CopterControl/Makefile | 1 + flight/CopterControl/System/inc/pios_config.h | 1 + flight/CopterControl/System/pios_board.c | 11 ++++ flight/Modules/ManualControl/manualcontrol.c | 11 ++++ flight/PiOS/Common/pios_usb_desc_hid_cdc.c | 65 ++++++++++++++++++- .../coptercontrol/board_hw_defs.c | 10 +++ shared/uavobjectdefinition/hwsettings.xml | 2 +- 7 files changed, 99 insertions(+), 2 deletions(-) diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index 7c5498806..9acfdff41 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -239,6 +239,7 @@ SRC += $(PIOSSTM32F10X)/pios_bl_helper.c SRC += $(PIOSSTM32F10X)/pios_usb.c SRC += $(PIOSSTM32F10X)/pios_usbhook.c SRC += $(PIOSSTM32F10X)/pios_usb_hid.c +SRC += $(PIOSSTM32F10X)/pios_usb_rctx.c SRC += $(PIOSSTM32F10X)/pios_usb_cdc.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c diff --git a/flight/CopterControl/System/inc/pios_config.h b/flight/CopterControl/System/inc/pios_config.h index 7c5857ab8..0edaecbf7 100644 --- a/flight/CopterControl/System/inc/pios_config.h +++ b/flight/CopterControl/System/inc/pios_config.h @@ -66,6 +66,7 @@ #define PIOS_INCLUDE_USART #define PIOS_INCLUDE_USB #define PIOS_INCLUDE_USB_HID +#define PIOS_INCLUDE_USB_RCTX #define PIOS_INCLUDE_USB_CDC #define PIOS_INCLUDE_COM #define PIOS_INCLUDE_SETTINGS diff --git a/flight/CopterControl/System/pios_board.c b/flight/CopterControl/System/pios_board.c index 42d5a4bfe..ccbae3058 100644 --- a/flight/CopterControl/System/pios_board.c +++ b/flight/CopterControl/System/pios_board.c @@ -67,6 +67,8 @@ uint32_t pios_com_vcp_id; uint32_t pios_com_gps_id; uint32_t pios_com_bridge_id; +uint32_t pios_usb_rctx_id; + /** * Configuration for MPU6000 chip */ @@ -358,6 +360,15 @@ void PIOS_Board_Init(void) { } #endif /* PIOS_INCLUDE_COM */ break; + case HWSETTINGS_USB_HIDPORT_RCTRANSMITTER: +#if defined(PIOS_INCLUDE_USB_RCTX) + { + if (PIOS_USB_RCTX_Init(&pios_usb_rctx_id, &pios_usb_rctx_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_USB_RCTX */ + break; } #endif /* PIOS_INCLUDE_USB_HID */ diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index cad5d065d..5123ff633 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -48,6 +48,10 @@ #include "positionactual.h" #include "baroaltitude.h" +#if defined(PIOS_INCLUDE_USB_RCTX) +#include "pios_usb_rctx.h" +#endif /* PIOS_INCLUDE_USB_RCTX */ + // Private constants #if defined(PIOS_MANUAL_STACK_SIZE) #define STACK_SIZE_BYTES PIOS_MANUAL_STACK_SIZE @@ -369,6 +373,13 @@ static void manualControlTask(void *parameters) // Update cmd object ManualControlCommandSet(&cmd); +#if defined(PIOS_INCLUDE_USB_RCTX) + if (pios_usb_rctx_id) { + PIOS_USB_RCTX_Update(pios_usb_rctx_id, + scaledChannel, + NELEMENTS(scaledChannel)); + } +#endif /* PIOS_INCLUDE_USB_RCTX */ } else { ManualControlCommandGet(&cmd); /* Under GCS control */ diff --git a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c index 1d4f0a9b2..a7eb2f9ea 100644 --- a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c +++ b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c @@ -51,7 +51,7 @@ static const struct usb_device_desc device_desc = { .bNumConfigurations = 1, }; -static const uint8_t hid_report_desc[36] = { +static const uint8_t hid_report_desc[88] = { HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_USAGE_PAGE), 0x9C, 0xFF, /* Usage Page 0xFF9C (Vendor Defined) */ HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), @@ -93,6 +93,69 @@ static const uint8_t hid_report_desc[36] = { 0x82, /* Volatile, Variable */ HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), + +/* 36 bytes to here */ + + /* Emulate a Joystick */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID), + 0x03, /* OpenPilot Emulated joystick */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_USAGE_PAGE), + 0x01, /* Usage Page 0x01 (Generic Desktop Controls) */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), + 0x00, /* Values range from min = 0x00 */ + HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_LOGICAL_MAX), + 0xFF, 0xFF, /* Values range to max = 0xFFFF */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), + 0x10, /* 16 bits wide */ + + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x04, /* Usage ID 0x0004 (Joystick) */ + HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), + 0x01, /* Application */ + + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x02, /* Usage ID 0x0002 (Pointer) */ + + HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), + 0x00, /* Physical */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x30, /* Usage ID 0x0030 (X) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x31, /* Usage ID 0x0031 (Y) */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), + 2, + HID_MAIN_ITEM_1 (HID_TAG_MAIN_INPUT), + 0x82, /* Data, Var, Abs, Vol */ + HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), + + HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), + 0x00, /* Physical */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x32, /* Usage ID 0x0032 (Z) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x33, /* Usage ID 0x0033 (Rx) */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), + 2, + HID_MAIN_ITEM_1 (HID_TAG_MAIN_INPUT), + 0x82, /* Data, Var, Abs, Vol */ + HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), + + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x34, /* Usage ID 0x0034 (Ry) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x35, /* Usage ID 0x0035 (Rz) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x36, /* Usage ID 0x0036 (Slider) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x37, /* Usage ID 0x0037 (Dial) */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), + 4, + HID_MAIN_ITEM_1 (HID_TAG_MAIN_INPUT), + 0x82, /* Data, Var, Abs, Vol */ + + HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), + +/* 88 bytes to here */ }; struct usb_config_hid_cdc { diff --git a/flight/board_hw_defs/coptercontrol/board_hw_defs.c b/flight/board_hw_defs/coptercontrol/board_hw_defs.c index 328fd44ce..cc6ec4552 100644 --- a/flight/board_hw_defs/coptercontrol/board_hw_defs.c +++ b/flight/board_hw_defs/coptercontrol/board_hw_defs.c @@ -1284,6 +1284,16 @@ const struct pios_usb_hid_cfg pios_usb_hid_cfg = { #endif /* PIOS_INCLUDE_USB_HID */ +#if defined(PIOS_INCLUDE_USB_RCTX) +#include + +const struct pios_usb_rctx_cfg pios_usb_rctx_cfg = { + .data_if = 2, + .data_tx_ep = 1, +}; + +#endif /* PIOS_INCLUDE_USB_RCTX */ + #if defined(PIOS_INCLUDE_USB_CDC) #include diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 0cee2a6d9..00c904dd4 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -15,7 +15,7 @@ - + From d44e24a1509959d3102b6b8cc7ed1334df4965ba Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Mon, 6 Aug 2012 11:42:44 -0400 Subject: [PATCH 38/52] hid joystick: add missing .h files --- flight/PiOS/inc/pios_usb_rctx.h | 4 +++ flight/PiOS/inc/pios_usb_rctx_priv.h | 48 ++++++++++++++++++++++++++++ 2 files changed, 52 insertions(+) create mode 100644 flight/PiOS/inc/pios_usb_rctx.h create mode 100644 flight/PiOS/inc/pios_usb_rctx_priv.h diff --git a/flight/PiOS/inc/pios_usb_rctx.h b/flight/PiOS/inc/pios_usb_rctx.h new file mode 100644 index 000000000..d925dc475 --- /dev/null +++ b/flight/PiOS/inc/pios_usb_rctx.h @@ -0,0 +1,4 @@ +extern uint32_t pios_usb_rctx_id; + +extern void PIOS_USB_RCTX_Update(uint32_t usbrctx_id, const float channels[], uint8_t num_channels); + diff --git a/flight/PiOS/inc/pios_usb_rctx_priv.h b/flight/PiOS/inc/pios_usb_rctx_priv.h new file mode 100644 index 000000000..cf9aab2b6 --- /dev/null +++ b/flight/PiOS/inc/pios_usb_rctx_priv.h @@ -0,0 +1,48 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB USB HID RC Transmitter/Joystick + * @brief Hardware communication layer + * @{ + * + * @file pios_usb_rctx_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief USB COM HID private definitions. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_RCTX_PRIV_H +#define PIOS_USB_RCTX_PRIV_H + +#include "pios_usb_rctx.h" + +struct pios_usb_rctx_cfg { + uint8_t data_if; + uint8_t data_tx_ep; +}; + +extern int32_t PIOS_USB_RCTX_Init(uint32_t * usbrctx_id, const struct pios_usb_rctx_cfg * cfg, uint32_t lower_id); + +#endif /* PIOS_USB_RCTX_PRIV_H */ + +/** + * @} + * @} + */ From 017d8c79c9fbcb6ad9d4c4be8dda856648247928 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Mon, 6 Aug 2012 11:49:03 -0400 Subject: [PATCH 39/52] hid joystick: add missing .c file This time for sure... --- flight/PiOS/STM32F10x/pios_usb_rctx.c | 192 ++++++++++++++++++++++++++ 1 file changed, 192 insertions(+) create mode 100644 flight/PiOS/STM32F10x/pios_usb_rctx.c diff --git a/flight/PiOS/STM32F10x/pios_usb_rctx.c b/flight/PiOS/STM32F10x/pios_usb_rctx.c new file mode 100644 index 000000000..e03ec8648 --- /dev/null +++ b/flight/PiOS/STM32F10x/pios_usb_rctx.c @@ -0,0 +1,192 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_RCTX USB RC Transmitter/Joystick Functions + * @brief PIOS USB implementation for a HID Joystick + * @notes This implements transmitter/joystick emulation over HID reports + * @{ + * + * @file pios_usb_rctx.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_USB_RCTX) + +#include "pios_usb.h" +#include "pios_usb_rctx_priv.h" + +/* STM32 USB Library Definitions */ +#include "usb_lib.h" + +#define PIOS_USB_RCTX_NUM_CHANNELS 8 + +enum pios_usb_rctx_dev_magic { + PIOS_USB_RCTX_DEV_MAGIC = 0xAB98B745, +}; + +struct pios_usb_rctx_dev { + enum pios_usb_rctx_dev_magic magic; + const struct pios_usb_rctx_cfg * cfg; + + uint32_t lower_id; + + struct { + uint8_t id; + uint16_t vals[PIOS_USB_RCTX_NUM_CHANNELS]; + } __attribute__((packed)) report; +}; + +static bool PIOS_USB_RCTX_validate(struct pios_usb_rctx_dev * usb_rctx_dev) +{ + return (usb_rctx_dev->magic == PIOS_USB_RCTX_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_usb_rctx_dev * PIOS_USB_RCTX_alloc(void) +{ + struct pios_usb_rctx_dev * usb_rctx_dev; + + usb_rctx_dev = (struct pios_usb_rctx_dev *)pvPortMalloc(sizeof(*usb_rctx_dev)); + if (!usb_rctx_dev) return(NULL); + + usb_rctx_dev->magic = PIOS_USB_RCTX_DEV_MAGIC; + return(usb_rctx_dev); +} +#else +static struct pios_usb_rctx_dev pios_usb_rctx_devs[PIOS_USB_RCTX_MAX_DEVS]; +static uint8_t pios_usb_rctx_num_devs; +static struct pios_usb_rctx_dev * PIOS_USB_RCTX_alloc(void) +{ + struct pios_usb_rctx_dev * usb_rctx_dev; + + if (pios_usb_rctx_num_devs >= PIOS_USB_RCTX_MAX_DEVS) { + return (NULL); + } + + usb_rctx_dev = &pios_usb_rctx_devs[pios_usb_rctx_num_devs++]; + usb_rctx_dev->magic = PIOS_USB_RCTX_DEV_MAGIC; + + return (usb_rctx_dev); +} +#endif + +static void PIOS_USB_RCTX_EP_IN_Callback(void); +static void PIOS_USB_RCTX_SendReport(struct pios_usb_rctx_dev * usb_rctx_dev); + +/* Need a better way to pull these in */ +extern void (*pEpInt_IN[7])(void); + +int32_t PIOS_USB_RCTX_Init(uint32_t * usbrctx_id, const struct pios_usb_rctx_cfg * cfg, uint32_t lower_id) +{ + PIOS_Assert(usbrctx_id); + PIOS_Assert(cfg); + + struct pios_usb_rctx_dev * usb_rctx_dev; + + usb_rctx_dev = (struct pios_usb_rctx_dev *) PIOS_USB_RCTX_alloc(); + if (!usb_rctx_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + usb_rctx_dev->cfg = cfg; + usb_rctx_dev->lower_id = lower_id; + + /* Set the initial report buffer */ + memset(&usb_rctx_dev->report, 0, sizeof(usb_rctx_dev->report)); + + pEpInt_IN[cfg->data_tx_ep - 1] = PIOS_USB_RCTX_EP_IN_Callback; + + *usbrctx_id = (uint32_t) usb_rctx_dev; + + return 0; + +out_fail: + return -1; +} + +static void PIOS_USB_RCTX_SendReport(struct pios_usb_rctx_dev * usb_rctx_dev) +{ +#if defined(PIOS_INCLUDE_FREERTOS) + bool need_yield = false; +#endif /* PIOS_INCLUDE_FREERTOS */ + + usb_rctx_dev->report.id = 3; /* FIXME: shouldn't hard-code this report ID */ + + UserToPMABufferCopy((uint8_t *) &usb_rctx_dev->report, + GetEPTxAddr(usb_rctx_dev->cfg->data_tx_ep), + sizeof(usb_rctx_dev->report)); + + SetEPTxCount(usb_rctx_dev->cfg->data_tx_ep, sizeof(usb_rctx_dev->report)); + SetEPTxValid(usb_rctx_dev->cfg->data_tx_ep); + +#if defined(PIOS_INCLUDE_FREERTOS) + if (need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ +} + +static void PIOS_USB_RCTX_EP_IN_Callback(void) +{ + struct pios_usb_rctx_dev * usb_rctx_dev = (struct pios_usb_rctx_dev *)pios_usb_rctx_id; + + bool valid = PIOS_USB_RCTX_validate(usb_rctx_dev); + PIOS_Assert(valid); + + if (!PIOS_USB_CheckAvailable(usb_rctx_dev->lower_id)) { + return; + } + + PIOS_USB_RCTX_SendReport(usb_rctx_dev); +} + +void PIOS_USB_RCTX_Update(uint32_t usbrctx_id, const float channels[], uint8_t num_channels) +{ + struct pios_usb_rctx_dev * usb_rctx_dev = (struct pios_usb_rctx_dev *)usbrctx_id; + + bool valid = PIOS_USB_RCTX_validate(usb_rctx_dev); + PIOS_Assert(valid); + + if (!PIOS_USB_CheckAvailable(usb_rctx_dev->lower_id)) { + return; + } + + for (uint8_t i = 0; + i < PIOS_USB_RCTX_NUM_CHANNELS && i < num_channels; + i++) { + /* + * Scaled channels range from -1 to +1. + * Move them to the USB HID range of 0 to 65535. + */ + usb_rctx_dev->report.vals[i] = (uint16_t) (32767.0f + (channels[i] * 32767.0f)); + } + + if (GetEPTxStatus(usb_rctx_dev->cfg->data_tx_ep) == EP_TX_VALID) { + /* Endpoint is already transmitting */ + return; + } + + PIOS_USB_RCTX_SendReport(usb_rctx_dev); +} + +#endif /* PIOS_INCLUDE_USB_RCTX */ From 94f6344fc51f838464e6d1f962c4f4e354415439 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Tue, 7 Aug 2012 21:34:25 -0400 Subject: [PATCH 40/52] hid joystick: restructure joystick HID report to work on windows --- flight/PiOS/Common/pios_usb_desc_hid_cdc.c | 87 +++++++++++++--------- flight/PiOS/inc/pios_usb_defs.h | 2 +- 2 files changed, 54 insertions(+), 35 deletions(-) diff --git a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c index a7eb2f9ea..434ca3dca 100644 --- a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c +++ b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c @@ -51,7 +51,7 @@ static const struct usb_device_desc device_desc = { .bNumConfigurations = 1, }; -static const uint8_t hid_report_desc[88] = { +static const uint8_t hid_report_desc[127] = { HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_USAGE_PAGE), 0x9C, 0xFF, /* Usage Page 0xFF9C (Vendor Defined) */ HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), @@ -97,57 +97,74 @@ static const uint8_t hid_report_desc[88] = { /* 36 bytes to here */ /* Emulate a Joystick */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_USAGE_PAGE), + 0x01, /* Usage Page 0x01 (Generic Desktop Controls) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x04, /* Usage ID 0x0004 (Joystick) */ + + HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), + 0x01, /* Application */ + HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), + 0x00, /* Physical */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID), 0x03, /* OpenPilot Emulated joystick */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_USAGE_PAGE), - 0x01, /* Usage Page 0x01 (Generic Desktop Controls) */ + + /* X + Y controls */ + + 0x02, /* Usage ID 0x0002 (Simulation Control */ + HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), + 0x30, 0x00, 0x01, 0x00, /* Usage ID 0x00010030 (Generic Desktop: X) */ + HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), + 0x31, 0x00, 0x01, 0x00, /* Usage ID 0x00010031 (Generic Desktop: Y) */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), 0x00, /* Values range from min = 0x00 */ HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_LOGICAL_MAX), 0xFF, 0xFF, /* Values range to max = 0xFFFF */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), 0x10, /* 16 bits wide */ - - HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), - 0x04, /* Usage ID 0x0004 (Joystick) */ - HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), - 0x01, /* Application */ - - HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), - 0x02, /* Usage ID 0x0002 (Pointer) */ - - HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), - 0x00, /* Physical */ - HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), - 0x30, /* Usage ID 0x0030 (X) */ - HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), - 0x31, /* Usage ID 0x0031 (Y) */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), 2, HID_MAIN_ITEM_1 (HID_TAG_MAIN_INPUT), 0x82, /* Data, Var, Abs, Vol */ - HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), - HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), - 0x00, /* Physical */ - HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), - 0x32, /* Usage ID 0x0032 (Z) */ - HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), - 0x33, /* Usage ID 0x0033 (Rx) */ + /* Y + Rx controls */ + + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_USAGE_PAGE), + 0x02, /* Usage ID 0x0002 (Simulation Control */ + HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), + 0x32, 0x00, 0x01, 0x00, /* Usage ID 0x00010032 (Generic Desktop: Z) */ + HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), + 0x33, 0x00, 0x01, 0x00, /* Usage ID 0x00010031 (Generic Desktop: Rx) */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), + 0x00, /* Values range from min = 0x00 */ + HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_LOGICAL_MAX), + 0xFF, 0xFF, /* Values range to max = 0xFFFF */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), + 0x10, /* 16 bits wide */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), 2, HID_MAIN_ITEM_1 (HID_TAG_MAIN_INPUT), 0x82, /* Data, Var, Abs, Vol */ - HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), - HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), - 0x34, /* Usage ID 0x0034 (Ry) */ - HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), - 0x35, /* Usage ID 0x0035 (Rz) */ - HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), - 0x36, /* Usage ID 0x0036 (Slider) */ - HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), - 0x37, /* Usage ID 0x0037 (Dial) */ + /* Ry, Rz, Slider + Dial controls */ + + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_USAGE_PAGE), + 0x02, /* Usage ID 0x0002 (Simulation Control */ + HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), + 0x34, 0x00, 0x01, 0x00, /* Usage ID 0x00010034 (Generic Desktop: Ry) */ + HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), + 0x35, 0x00, 0x01, 0x00, /* Usage ID 0x00010035 (Generic Desktop: Rz) */ + HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), + 0x36, 0x00, 0x01, 0x00, /* Usage ID 0x00010036 (Generic Desktop: Slider) */ + HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), + 0x37, 0x00, 0x01, 0x00, /* Usage ID 0x00010037 (Generic Desktop: Dial) */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), + 0x00, /* Values range from min = 0x00 */ + HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_LOGICAL_MAX), + 0xFF, 0xFF, /* Values range to max = 0xFFFF */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), + 0x10, /* 16 bits wide */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), 4, HID_MAIN_ITEM_1 (HID_TAG_MAIN_INPUT), @@ -155,7 +172,9 @@ static const uint8_t hid_report_desc[88] = { HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), -/* 88 bytes to here */ + HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), + +/* 127 bytes to here */ }; struct usb_config_hid_cdc { diff --git a/flight/PiOS/inc/pios_usb_defs.h b/flight/PiOS/inc/pios_usb_defs.h index be827a494..ea54306a7 100644 --- a/flight/PiOS/inc/pios_usb_defs.h +++ b/flight/PiOS/inc/pios_usb_defs.h @@ -147,7 +147,7 @@ enum usb_ep_attr { #define HID_LOCAL_ITEM_0(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_LOCAL, HID_ITEM_SIZE_0) #define HID_LOCAL_ITEM_1(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_LOCAL, HID_ITEM_SIZE_1) #define HID_LOCAL_ITEM_2(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_LOCAL, HID_ITEM_SIZE_2) -#define HID_LOCAL_ITEM_3(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_LOCAL, HID_ITEM_SIZE_3) +#define HID_LOCAL_ITEM_4(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_LOCAL, HID_ITEM_SIZE_4) struct usb_device_desc { uint8_t bLength; From 449c7aab7a8c4820caa9376c09eb3c117d4c876a Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Wed, 8 Aug 2012 00:50:03 -0400 Subject: [PATCH 41/52] hid joystick: use 32-bits to represent max range --- flight/PiOS/Common/pios_usb_desc_hid_cdc.c | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c index 434ca3dca..87a81af43 100644 --- a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c +++ b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c @@ -51,7 +51,7 @@ static const struct usb_device_desc device_desc = { .bNumConfigurations = 1, }; -static const uint8_t hid_report_desc[127] = { +static const uint8_t hid_report_desc[133] = { HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_USAGE_PAGE), 0x9C, 0xFF, /* Usage Page 0xFF9C (Vendor Defined) */ HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), @@ -119,8 +119,8 @@ static const uint8_t hid_report_desc[127] = { 0x31, 0x00, 0x01, 0x00, /* Usage ID 0x00010031 (Generic Desktop: Y) */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), 0x00, /* Values range from min = 0x00 */ - HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_LOGICAL_MAX), - 0xFF, 0xFF, /* Values range to max = 0xFFFF */ + HID_GLOBAL_ITEM_4 (HID_TAG_GLOBAL_LOGICAL_MAX), + 0xFF, 0xFF, 0x00, 0x00, /* Values range to max = 0x0000FFFF */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), 0x10, /* 16 bits wide */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), @@ -138,8 +138,8 @@ static const uint8_t hid_report_desc[127] = { 0x33, 0x00, 0x01, 0x00, /* Usage ID 0x00010031 (Generic Desktop: Rx) */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), 0x00, /* Values range from min = 0x00 */ - HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_LOGICAL_MAX), - 0xFF, 0xFF, /* Values range to max = 0xFFFF */ + HID_GLOBAL_ITEM_4 (HID_TAG_GLOBAL_LOGICAL_MAX), + 0xFF, 0xFF, 0x00, 0x00, /* Values range to max = 0x0000FFFF */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), 0x10, /* 16 bits wide */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), @@ -161,8 +161,8 @@ static const uint8_t hid_report_desc[127] = { 0x37, 0x00, 0x01, 0x00, /* Usage ID 0x00010037 (Generic Desktop: Dial) */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), 0x00, /* Values range from min = 0x00 */ - HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_LOGICAL_MAX), - 0xFF, 0xFF, /* Values range to max = 0xFFFF */ + HID_GLOBAL_ITEM_4 (HID_TAG_GLOBAL_LOGICAL_MAX), + 0xFF, 0xFF, 0x00, 0x00, /* Values range to max = 0x0000FFFF */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), 0x10, /* 16 bits wide */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), @@ -174,7 +174,7 @@ static const uint8_t hid_report_desc[127] = { HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), -/* 127 bytes to here */ +/* 133 bytes to here */ }; struct usb_config_hid_cdc { From 030d9e84f9e8f04152f729f225f65af111f06561 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Wed, 8 Aug 2012 10:15:08 -0400 Subject: [PATCH 42/52] hid joystick: remove unnecessary usage page definitions --- flight/PiOS/Common/pios_usb_desc_hid_cdc.c | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c index 87a81af43..ff4b9d4a1 100644 --- a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c +++ b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c @@ -51,7 +51,7 @@ static const struct usb_device_desc device_desc = { .bNumConfigurations = 1, }; -static const uint8_t hid_report_desc[133] = { +static const uint8_t hid_report_desc[127] = { HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_USAGE_PAGE), 0x9C, 0xFF, /* Usage Page 0xFF9C (Vendor Defined) */ HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), @@ -108,11 +108,9 @@ static const uint8_t hid_report_desc[133] = { 0x00, /* Physical */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID), 0x03, /* OpenPilot Emulated joystick */ - HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_USAGE_PAGE), /* X + Y controls */ - 0x02, /* Usage ID 0x0002 (Simulation Control */ HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), 0x30, 0x00, 0x01, 0x00, /* Usage ID 0x00010030 (Generic Desktop: X) */ HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), @@ -130,8 +128,6 @@ static const uint8_t hid_report_desc[133] = { /* Y + Rx controls */ - HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_USAGE_PAGE), - 0x02, /* Usage ID 0x0002 (Simulation Control */ HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), 0x32, 0x00, 0x01, 0x00, /* Usage ID 0x00010032 (Generic Desktop: Z) */ HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), @@ -149,8 +145,6 @@ static const uint8_t hid_report_desc[133] = { /* Ry, Rz, Slider + Dial controls */ - HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_USAGE_PAGE), - 0x02, /* Usage ID 0x0002 (Simulation Control */ HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), 0x34, 0x00, 0x01, 0x00, /* Usage ID 0x00010034 (Generic Desktop: Ry) */ HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), @@ -174,7 +168,7 @@ static const uint8_t hid_report_desc[133] = { HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), -/* 133 bytes to here */ +/* 127 bytes to here */ }; struct usb_config_hid_cdc { From 5902c19cc3294a22ffcf618e57c9c58338576230 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Wed, 8 Aug 2012 10:38:43 -0400 Subject: [PATCH 43/52] hid joystick: compress local usages since they're all in the same page --- flight/PiOS/Common/pios_usb_desc_hid_cdc.c | 36 +++++++++++----------- 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c index ff4b9d4a1..f778bea04 100644 --- a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c +++ b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c @@ -51,7 +51,7 @@ static const struct usb_device_desc device_desc = { .bNumConfigurations = 1, }; -static const uint8_t hid_report_desc[127] = { +static const uint8_t hid_report_desc[103] = { HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_USAGE_PAGE), 0x9C, 0xFF, /* Usage Page 0xFF9C (Vendor Defined) */ HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), @@ -111,10 +111,10 @@ static const uint8_t hid_report_desc[127] = { /* X + Y controls */ - HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), - 0x30, 0x00, 0x01, 0x00, /* Usage ID 0x00010030 (Generic Desktop: X) */ - HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), - 0x31, 0x00, 0x01, 0x00, /* Usage ID 0x00010031 (Generic Desktop: Y) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x30, /* Usage ID 0x00010030 (Generic Desktop: X) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x31, /* Usage ID 0x00010031 (Generic Desktop: Y) */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), 0x00, /* Values range from min = 0x00 */ HID_GLOBAL_ITEM_4 (HID_TAG_GLOBAL_LOGICAL_MAX), @@ -128,10 +128,10 @@ static const uint8_t hid_report_desc[127] = { /* Y + Rx controls */ - HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), - 0x32, 0x00, 0x01, 0x00, /* Usage ID 0x00010032 (Generic Desktop: Z) */ - HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), - 0x33, 0x00, 0x01, 0x00, /* Usage ID 0x00010031 (Generic Desktop: Rx) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x32, /* Usage ID 0x00010032 (Generic Desktop: Z) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x33, /* Usage ID 0x00010031 (Generic Desktop: Rx) */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), 0x00, /* Values range from min = 0x00 */ HID_GLOBAL_ITEM_4 (HID_TAG_GLOBAL_LOGICAL_MAX), @@ -145,14 +145,14 @@ static const uint8_t hid_report_desc[127] = { /* Ry, Rz, Slider + Dial controls */ - HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), - 0x34, 0x00, 0x01, 0x00, /* Usage ID 0x00010034 (Generic Desktop: Ry) */ - HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), - 0x35, 0x00, 0x01, 0x00, /* Usage ID 0x00010035 (Generic Desktop: Rz) */ - HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), - 0x36, 0x00, 0x01, 0x00, /* Usage ID 0x00010036 (Generic Desktop: Slider) */ - HID_LOCAL_ITEM_4 (HID_TAG_LOCAL_USAGE), - 0x37, 0x00, 0x01, 0x00, /* Usage ID 0x00010037 (Generic Desktop: Dial) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x34, /* Usage ID 0x00010034 (Generic Desktop: Ry) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x35, /* Usage ID 0x00010035 (Generic Desktop: Rz) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x36, /* Usage ID 0x00010036 (Generic Desktop: Slider) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x37, /* Usage ID 0x00010037 (Generic Desktop: Dial) */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), 0x00, /* Values range from min = 0x00 */ HID_GLOBAL_ITEM_4 (HID_TAG_GLOBAL_LOGICAL_MAX), @@ -168,7 +168,7 @@ static const uint8_t hid_report_desc[127] = { HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), -/* 127 bytes to here */ +/* 103 bytes to here */ }; struct usb_config_hid_cdc { From 07fde38887abf4ccd9d3b5c818b51c4363cd8a21 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Fri, 10 Aug 2012 23:29:34 -0400 Subject: [PATCH 44/52] hid joystick: factor out min/max range from report items --- flight/PiOS/Common/pios_usb_desc_hid_cdc.c | 21 +++++++-------------- 1 file changed, 7 insertions(+), 14 deletions(-) diff --git a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c index f778bea04..747eda3d4 100644 --- a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c +++ b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c @@ -51,7 +51,7 @@ static const struct usb_device_desc device_desc = { .bNumConfigurations = 1, }; -static const uint8_t hid_report_desc[103] = { +static const uint8_t hid_report_desc[89] = { HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_USAGE_PAGE), 0x9C, 0xFF, /* Usage Page 0xFF9C (Vendor Defined) */ HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), @@ -102,6 +102,11 @@ static const uint8_t hid_report_desc[103] = { HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), 0x04, /* Usage ID 0x0004 (Joystick) */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), + 0x00, /* Values range from min = 0x00 */ + HID_GLOBAL_ITEM_4 (HID_TAG_GLOBAL_LOGICAL_MAX), + 0xFF, 0xFF, 0x00, 0x00, /* Values range to max = 0x0000FFFF */ + HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), 0x01, /* Application */ HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), @@ -115,10 +120,6 @@ static const uint8_t hid_report_desc[103] = { 0x30, /* Usage ID 0x00010030 (Generic Desktop: X) */ HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), 0x31, /* Usage ID 0x00010031 (Generic Desktop: Y) */ - HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), - 0x00, /* Values range from min = 0x00 */ - HID_GLOBAL_ITEM_4 (HID_TAG_GLOBAL_LOGICAL_MAX), - 0xFF, 0xFF, 0x00, 0x00, /* Values range to max = 0x0000FFFF */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), 0x10, /* 16 bits wide */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), @@ -132,10 +133,6 @@ static const uint8_t hid_report_desc[103] = { 0x32, /* Usage ID 0x00010032 (Generic Desktop: Z) */ HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), 0x33, /* Usage ID 0x00010031 (Generic Desktop: Rx) */ - HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), - 0x00, /* Values range from min = 0x00 */ - HID_GLOBAL_ITEM_4 (HID_TAG_GLOBAL_LOGICAL_MAX), - 0xFF, 0xFF, 0x00, 0x00, /* Values range to max = 0x0000FFFF */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), 0x10, /* 16 bits wide */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), @@ -153,10 +150,6 @@ static const uint8_t hid_report_desc[103] = { 0x36, /* Usage ID 0x00010036 (Generic Desktop: Slider) */ HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), 0x37, /* Usage ID 0x00010037 (Generic Desktop: Dial) */ - HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), - 0x00, /* Values range from min = 0x00 */ - HID_GLOBAL_ITEM_4 (HID_TAG_GLOBAL_LOGICAL_MAX), - 0xFF, 0xFF, 0x00, 0x00, /* Values range to max = 0x0000FFFF */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), 0x10, /* 16 bits wide */ HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), @@ -168,7 +161,7 @@ static const uint8_t hid_report_desc[103] = { HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), -/* 103 bytes to here */ +/* 89 bytes to here */ }; struct usb_config_hid_cdc { From 49c153003c470cc6d3aca59fc2a20cedf5b39e60 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Fri, 10 Aug 2012 23:36:06 -0400 Subject: [PATCH 45/52] hid joystick: use linearly scaled channels Scales each channel only based on max and min calibrated values. The neutral value is now ignored so the joystick sees a linear range between min and max. This is particularly useful to allow the full range of values for throttle to be passed through to the joystick. --- flight/Modules/ManualControl/manualcontrol.c | 6 ++-- flight/PiOS/STM32F10x/pios_usb_rctx.c | 31 ++++++++++++++++---- flight/PiOS/inc/pios_usb_rctx.h | 3 +- 3 files changed, 30 insertions(+), 10 deletions(-) diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 5123ff633..7d0e78881 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -376,8 +376,10 @@ static void manualControlTask(void *parameters) #if defined(PIOS_INCLUDE_USB_RCTX) if (pios_usb_rctx_id) { PIOS_USB_RCTX_Update(pios_usb_rctx_id, - scaledChannel, - NELEMENTS(scaledChannel)); + cmd.Channel, + settings.ChannelMin, + settings.ChannelMax, + NELEMENTS(cmd.Channel)); } #endif /* PIOS_INCLUDE_USB_RCTX */ diff --git a/flight/PiOS/STM32F10x/pios_usb_rctx.c b/flight/PiOS/STM32F10x/pios_usb_rctx.c index e03ec8648..3976eafc3 100644 --- a/flight/PiOS/STM32F10x/pios_usb_rctx.c +++ b/flight/PiOS/STM32F10x/pios_usb_rctx.c @@ -160,7 +160,7 @@ static void PIOS_USB_RCTX_EP_IN_Callback(void) PIOS_USB_RCTX_SendReport(usb_rctx_dev); } -void PIOS_USB_RCTX_Update(uint32_t usbrctx_id, const float channels[], uint8_t num_channels) +void PIOS_USB_RCTX_Update(uint32_t usbrctx_id, const uint16_t channel[], const int16_t channel_min[], const int16_t channel_max[], uint8_t num_channels) { struct pios_usb_rctx_dev * usb_rctx_dev = (struct pios_usb_rctx_dev *)usbrctx_id; @@ -174,11 +174,30 @@ void PIOS_USB_RCTX_Update(uint32_t usbrctx_id, const float channels[], uint8_t n for (uint8_t i = 0; i < PIOS_USB_RCTX_NUM_CHANNELS && i < num_channels; i++) { - /* - * Scaled channels range from -1 to +1. - * Move them to the USB HID range of 0 to 65535. - */ - usb_rctx_dev->report.vals[i] = (uint16_t) (32767.0f + (channels[i] * 32767.0f)); + int16_t min = channel_min[i]; + int16_t max = channel_max[i]; + uint16_t val = channel[i]; + + if (channel_min[i] > channel_max[i]) { + /* This channel is reversed, flip min and max */ + min = channel_max[i]; + max = channel_min[i]; + + /* and flip val to be an offset from the lower end of the range */ + val = channel_min[i] - channel[i] + channel_max[i]; + } + + /* Scale channel linearly between min and max */ + if (min == max) { + val = 0; + } else { + if (val < min) val = min; + if (val > max) val = max; + + val = (val - min) * (65535 / (max - min)); + } + + usb_rctx_dev->report.vals[i] = val; } if (GetEPTxStatus(usb_rctx_dev->cfg->data_tx_ep) == EP_TX_VALID) { diff --git a/flight/PiOS/inc/pios_usb_rctx.h b/flight/PiOS/inc/pios_usb_rctx.h index d925dc475..ea07a6d7f 100644 --- a/flight/PiOS/inc/pios_usb_rctx.h +++ b/flight/PiOS/inc/pios_usb_rctx.h @@ -1,4 +1,3 @@ extern uint32_t pios_usb_rctx_id; -extern void PIOS_USB_RCTX_Update(uint32_t usbrctx_id, const float channels[], uint8_t num_channels); - +extern void PIOS_USB_RCTX_Update(uint32_t usbrctx_id, const uint16_t channel[], const int16_t channel_min[], const int16_t channel_max[], uint8_t num_channels); From bbe86332de2a9342d40f5e46f4dcc89c3d73b59d Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 11 Aug 2012 11:28:44 -0400 Subject: [PATCH 46/52] hid joystick: mentioned new feature in HISTORY file --- HISTORY.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/HISTORY.txt b/HISTORY.txt index 838f25d05..1e9bcb162 100644 --- a/HISTORY.txt +++ b/HISTORY.txt @@ -1,5 +1,9 @@ Short summary of changes. For a complete list see the git log. +2012-08-11 +CopterControl can now emulate an 8-channel USB HID joystick. Primarily, +this lets you use any RC transmitter with flight simulators on your PC. + 2012-07-20 AeroSimRC simulator plugin is now included into the Windows distribution (will be installed into .../OpenPilot/misc/AeroSIM-RC directory). Still From 63c167c18333b05054f5bd77813ddb092725c14d Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 11 Aug 2012 18:46:45 -0400 Subject: [PATCH 47/52] taskinfo: also track Event thread's stack usage and CPU utilization The event dispatcher thread is started differently than most other threads so it was missed in the taskinfo tracking information. Now it's also included. --- flight/UAVObjects/eventdispatcher.c | 3 +++ shared/uavobjectdefinition/taskinfo.xml | 6 +++--- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/flight/UAVObjects/eventdispatcher.c b/flight/UAVObjects/eventdispatcher.c index a5a728b62..e0ffbc99a 100644 --- a/flight/UAVObjects/eventdispatcher.c +++ b/flight/UAVObjects/eventdispatcher.c @@ -280,6 +280,9 @@ static void eventTask() int32_t delayMs; EventCallbackInfo evInfo; + /* Must do this in task context to ensure that TaskMonitor has already finished its init */ + TaskMonitorAdd(TASKINFO_RUNNING_EVENTDISPATCHER, eventTaskHandle); + // Initialize time timeToNextUpdateMs = xTaskGetTickCount()*portTICK_RATE_MS; diff --git a/shared/uavobjectdefinition/taskinfo.xml b/shared/uavobjectdefinition/taskinfo.xml index 40f0d4bdf..551167501 100644 --- a/shared/uavobjectdefinition/taskinfo.xml +++ b/shared/uavobjectdefinition/taskinfo.xml @@ -1,9 +1,9 @@ Task information - - - + + + From 29ab1d8cf300033e53bfeca10042badf0c2f5d92 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 11 Aug 2012 19:46:00 -0400 Subject: [PATCH 48/52] actuator: factor out settings updates from main loop --- flight/Modules/Actuator/actuator.c | 229 ++++++++++++++------------- flight/PiOS.posix/inc/pios_servo.h | 2 +- flight/PiOS.posix/posix/pios_servo.c | 2 +- flight/PiOS.win32/win32/pios_servo.c | 2 +- flight/PiOS/STM32F10x/pios_servo.c | 2 +- flight/PiOS/STM32F4xx/pios_servo.c | 2 +- flight/PiOS/inc/pios_servo.h | 2 +- 7 files changed, 123 insertions(+), 118 deletions(-) diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c index 775b71360..e59d50957 100644 --- a/flight/Modules/Actuator/actuator.c +++ b/flight/Modules/Actuator/actuator.c @@ -65,24 +65,25 @@ static xQueueHandle queue; static xTaskHandle taskHandle; static float lastResult[MAX_MIX_ACTUATORS]={0,0,0,0,0,0,0,0}; -static float lastFilteredResult[MAX_MIX_ACTUATORS]={0,0,0,0,0,0,0,0}; static float filterAccumulator[MAX_MIX_ACTUATORS]={0,0,0,0,0,0,0,0}; // used to inform the actuator thread that actuator update rate is changed -static uint8_t updateRateChanged = 0; +static volatile bool actuator_settings_updated; +// used to inform the actuator thread that mixer settings are changed +static volatile bool mixer_settings_updated; // Private functions static void actuatorTask(void* parameters); -static void actuator_update_rate(UAVObjEvent *); static int16_t scaleChannel(float value, int16_t max, int16_t min, int16_t neutral); -static void setFailsafe(); +static void setFailsafe(const ActuatorSettingsData * actuatorSettings, const MixerSettingsData * mixerSettings); static float MixerCurve(const float throttle, const float* curve, uint8_t elements); -static bool set_channel(uint8_t mixer_channel, uint16_t value); -static void change_update_rate(); +static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSettingsData * actuatorSettings); +static void actuator_update_rate_if_changed(const ActuatorSettingsData * actuatorSettings, bool force_update); +static void MixerSettingsUpdatedCb(UAVObjEvent * ev); +static void ActuatorSettingsUpdatedCb(UAVObjEvent * ev); float ProcessMixer(const int index, const float curve1, const float curve2, - MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, + const MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, const float period); -static uint16_t lastChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM] = {0,0,0,0}; //this structure is equivalent to the UAVObjects for one mixer. typedef struct { uint8_t type; @@ -109,22 +110,26 @@ int32_t ActuatorStart() */ int32_t ActuatorInitialize() { - // Create object queue - queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); - + // Register for notification of changes to ActuatorSettings ActuatorSettingsInitialize(); - ActuatorDesiredInitialize(); - MixerSettingsInitialize(); - ActuatorCommandInitialize(); -#if defined(DIAGNOSTICS) - MixerStatusInitialize(); -#endif + ActuatorSettingsConnectCallback(ActuatorSettingsUpdatedCb); - // Listen for ExampleObject1 updates + // Register for notification of changes to MixerSettings + MixerSettingsInitialize(); + MixerSettingsConnectCallback(MixerSettingsUpdatedCb); + + // Listen for ActuatorDesired updates (Primary input to this module) + ActuatorDesiredInitialize(); + queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); ActuatorDesiredConnectQueue(queue); - // If settings change, update the output rate - ActuatorSettingsConnectCallback(actuator_update_rate); + // Primary output of this module + ActuatorCommandInitialize(); + +#if defined(DIAGNOSTICS) + // UAVO only used for inspecting the internal status of the mixer during debug + MixerStatusInitialize(); +#endif return 0; } @@ -151,22 +156,25 @@ static void actuatorTask(void* parameters) float dT = 0.0f; ActuatorCommandData command; - MixerSettingsData mixerSettings; ActuatorDesiredData desired; MixerStatusData mixerStatus; FlightStatusData flightStatus; - uint8_t MotorsSpinWhileArmed; - int16_t ChannelMax[ACTUATORCOMMAND_CHANNEL_NUMELEM]; - int16_t ChannelMin[ACTUATORCOMMAND_CHANNEL_NUMELEM]; - int16_t ChannelNeutral[ACTUATORCOMMAND_CHANNEL_NUMELEM]; + /* Read initial values of ActuatorSettings */ + ActuatorSettingsData actuatorSettings; + actuator_settings_updated = false; + ActuatorSettingsGet(&actuatorSettings); - change_update_rate(); - - float * status = (float *)&mixerStatus; //access status objects as an array of floats + /* Read initial values of MixerSettings */ + MixerSettingsData mixerSettings; + mixer_settings_updated = false; + MixerSettingsGet(&mixerSettings); + + /* Force an initial configuration of the actuator update rates */ + actuator_update_rate_if_changed(&actuatorSettings, true); // Go to the neutral (failsafe) values until an ActuatorDesired update is received - setFailsafe(); + setFailsafe(&actuatorSettings, &mixerSettings); // Main task loop lastSysTime = xTaskGetTickCount(); @@ -174,19 +182,26 @@ static void actuatorTask(void* parameters) { PIOS_WDG_UpdateFlag(PIOS_WDG_ACTUATOR); - // Wait until the ActuatorDesired object is updated, if a timeout then go to failsafe - if ( xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE ) - { - setFailsafe(); + // Wait until the ActuatorDesired object is updated + uint8_t rc = xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS); + + /* Process settings updated events even in timeout case so we always act on the latest settings */ + if (actuator_settings_updated) { + actuator_settings_updated = false; + ActuatorSettingsGet (&actuatorSettings); + actuator_update_rate_if_changed (&actuatorSettings, false); + } + if (mixer_settings_updated) { + mixer_settings_updated = false; + MixerSettingsGet (&mixerSettings); + } + + if (rc != pdTRUE) { + /* Update of ActuatorDesired timed out. Go to failsafe */ + setFailsafe(&actuatorSettings, &mixerSettings); continue; } - if(updateRateChanged!=0) - { - change_update_rate(); - updateRateChanged=0; - } - // Check how long since last update thisSysTime = xTaskGetTickCount(); if(thisSysTime > lastSysTime) // reuse dt in case of wraparound @@ -194,18 +209,12 @@ static void actuatorTask(void* parameters) lastSysTime = thisSysTime; FlightStatusGet(&flightStatus); - MixerSettingsGet (&mixerSettings); ActuatorDesiredGet(&desired); ActuatorCommandGet(&command); #if defined(DIAGNOSTICS) MixerStatusGet(&mixerStatus); #endif - ActuatorSettingsMotorsSpinWhileArmedGet(&MotorsSpinWhileArmed); - ActuatorSettingsChannelMaxGet(ChannelMax); - ActuatorSettingsChannelMinGet(ChannelMin); - ActuatorSettingsChannelNeutralGet(ChannelNeutral); - int nMixers = 0; Mixer_t * mixers = (Mixer_t *)&mixerSettings.Mixer1Type; for(int ct=0; ct < MAX_MIX_ACTUATORS; ct++) @@ -217,7 +226,7 @@ static void actuatorTask(void* parameters) } if((nMixers < 2) && !ActuatorCommandReadOnly()) //Nothing can fly with less than two mixers. { - setFailsafe(); // So that channels like PWM buzzer keep working + setFailsafe(&actuatorSettings, &mixerSettings); // So that channels like PWM buzzer keep working continue; } @@ -225,7 +234,7 @@ static void actuatorTask(void* parameters) bool armed = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED; bool positiveThrottle = desired.Throttle >= 0.00f; - bool spinWhileArmed = MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE; + bool spinWhileArmed = actuatorSettings.MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE; float curve1 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve1,MIXERSETTINGS_THROTTLECURVE1_NUMELEM); @@ -264,6 +273,8 @@ static void actuatorTask(void* parameters) break; } + float * status = (float *)&mixerStatus; //access status objects as an array of floats + for(int ct=0; ct < MAX_MIX_ACTUATORS; ct++) { if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_DISABLED) { @@ -337,9 +348,9 @@ static void actuatorTask(void* parameters) for(int i = 0; i < MAX_MIX_ACTUATORS; i++) command.Channel[i] = scaleChannel(status[i], - ChannelMax[i], - ChannelMin[i], - ChannelNeutral[i]); + actuatorSettings.ChannelMax[i], + actuatorSettings.ChannelMin[i], + actuatorSettings.ChannelNeutral[i]); // Store update time command.UpdateTime = 1000.0f*dT; @@ -361,7 +372,7 @@ static void actuatorTask(void* parameters) for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) { - success &= set_channel(n, command.Channel[n]); + success &= set_channel(n, command.Channel[n], &actuatorSettings); } if(!success) { @@ -379,15 +390,18 @@ static void actuatorTask(void* parameters) *Process mixing for one actuator */ float ProcessMixer(const int index, const float curve1, const float curve2, - MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, const float period) + const MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, const float period) { - Mixer_t * mixers = (Mixer_t *)&mixerSettings->Mixer1Type; //pointer to array of mixers in UAVObjects - Mixer_t * mixer = &mixers[index]; + static float lastFilteredResult[MAX_MIX_ACTUATORS]; + const Mixer_t * mixers = (Mixer_t *)&mixerSettings->Mixer1Type; //pointer to array of mixers in UAVObjects + const Mixer_t * mixer = &mixers[index]; + float result = (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE1] / 128.0f) * curve1) + - (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE2] / 128.0f) * curve2) + - (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_ROLL] / 128.0f) * desired->Roll) + - (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_PITCH] / 128.0f) * desired->Pitch) + - (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_YAW] / 128.0f) * desired->Yaw); + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE2] / 128.0f) * curve2) + + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_ROLL] / 128.0f) * desired->Roll) + + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_PITCH] / 128.0f) * desired->Pitch) + + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_YAW] / 128.0f) * desired->Yaw); + if(mixer->type == MIXERSETTINGS_MIXER1TYPE_MOTOR) { if(result < 0.0f) //idle throttle @@ -501,19 +515,13 @@ static int16_t scaleChannel(float value, int16_t max, int16_t min, int16_t neutr /** * Set actuator output to the neutral values (failsafe) */ -static void setFailsafe() +static void setFailsafe(const ActuatorSettingsData * actuatorSettings, const MixerSettingsData * mixerSettings) { - /* grab only the modules parts that we are going to use */ - int16_t ChannelMin[ACTUATORCOMMAND_CHANNEL_NUMELEM]; - ActuatorSettingsChannelMinGet(ChannelMin); - int16_t ChannelNeutral[ACTUATORCOMMAND_CHANNEL_NUMELEM]; - ActuatorSettingsChannelNeutralGet(ChannelNeutral); + /* grab only the parts that we are going to use */ int16_t Channel[ACTUATORCOMMAND_CHANNEL_NUMELEM]; ActuatorCommandChannelGet(Channel); - MixerSettingsData mixerSettings; - MixerSettingsGet (&mixerSettings); - Mixer_t * mixers = (Mixer_t *)&mixerSettings.Mixer1Type; //pointer to array of mixers in UAVObjects + const Mixer_t * mixers = (Mixer_t *)&mixerSettings->Mixer1Type; //pointer to array of mixers in UAVObjects // Reset ActuatorCommand to safe values for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) @@ -521,11 +529,11 @@ static void setFailsafe() if(mixers[n].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) { - Channel[n] = ChannelMin[n]; + Channel[n] = actuatorSettings->ChannelMin[n]; } else if(mixers[n].type == MIXERSETTINGS_MIXER1TYPE_SERVO) { - Channel[n] = ChannelNeutral[n]; + Channel[n] = actuatorSettings->ChannelNeutral[n]; } else { @@ -541,54 +549,22 @@ static void setFailsafe() // Update servo outputs for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) { - set_channel(n, Channel[n]); + set_channel(n, Channel[n], actuatorSettings); } // Update output object's parts that we changed ActuatorCommandChannelSet(Channel); } - -/** - * @brief Update the servo update rate - */ -static void actuator_update_rate(UAVObjEvent * ev) -{ - uint16_t ChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM]; - // ActuatoSettings are not changed - if ( ev->obj != ActuatorSettingsHandle() ) - return; - - ActuatorSettingsChannelUpdateFreqGet(ChannelUpdateFreq); - // check if the any rate setting is changed - if (lastChannelUpdateFreq[0]!=0 && memcmp(&lastChannelUpdateFreq[0], &ChannelUpdateFreq[0], sizeof(int16_t) * ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM) ==0) - return; - // signal to the actuator task that ChannelUpdateFreq are changed - updateRateChanged = 1; -} -/** - * @brief Change the update rates according to the ActuatorSettingsChannelUpdateFreq. - */ -static void change_update_rate() -{ - uint16_t ChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM]; - // save the new rates - ActuatorSettingsChannelUpdateFreqGet(ChannelUpdateFreq); - memcpy(lastChannelUpdateFreq, ChannelUpdateFreq, sizeof(int16_t) * ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM); - PIOS_Servo_SetHz(&ChannelUpdateFreq[0], ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM); -} - #if defined(ARCH_POSIX) || defined(ARCH_WIN32) -static bool set_channel(uint8_t mixer_channel, uint16_t value) { +static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSettingsData * actuatorSettings) +{ return true; } #else -static bool set_channel(uint8_t mixer_channel, uint16_t value) { - - ActuatorSettingsData settings; - ActuatorSettingsGet(&settings); - - switch(settings.ChannelType[mixer_channel]) { +static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSettingsData * actuatorSettings) +{ + switch(actuatorSettings->ChannelType[mixer_channel]) { case ACTUATORSETTINGS_CHANNELTYPE_PWMALARMBUZZER: { // This is for buzzers that take a PWM input @@ -631,18 +607,18 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) { lastSysTime = thisSysTime; } } - PIOS_Servo_Set( settings.ChannelAddr[mixer_channel], - buzzOn?settings.ChannelMax[mixer_channel]:settings.ChannelMin[mixer_channel]); + PIOS_Servo_Set(actuatorSettings->ChannelAddr[mixer_channel], + buzzOn?actuatorSettings->ChannelMax[mixer_channel]:actuatorSettings->ChannelMin[mixer_channel]); return true; } case ACTUATORSETTINGS_CHANNELTYPE_PWM: - PIOS_Servo_Set(settings.ChannelAddr[mixer_channel], value); + PIOS_Servo_Set(actuatorSettings->ChannelAddr[mixer_channel], value); return true; #if defined(PIOS_INCLUDE_I2C_ESC) case ACTUATORSETTINGS_CHANNELTYPE_MK: - return PIOS_SetMKSpeed(settings.ChannelAddr[mixer_channel],value); + return PIOS_SetMKSpeed(actuatorSettings->ChannelAddr[mixer_channel],value); case ACTUATORSETTINGS_CHANNELTYPE_ASTEC4: - return PIOS_SetAstec4Speed(settings.ChannelAddr[mixer_channel],value); + return PIOS_SetAstec4Speed(actuatorSettings->ChannelAddr[mixer_channel],value); break; #endif default: @@ -654,6 +630,35 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) { } #endif +/** + * @brief Update the servo update rate + */ +static void actuator_update_rate_if_changed(const ActuatorSettingsData * actuatorSettings, bool force_update) +{ + static uint16_t prevChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM]; + + // check if the any rate setting is changed + if (force_update || + memcmp (prevChannelUpdateFreq, + actuatorSettings->ChannelUpdateFreq, + sizeof(prevChannelUpdateFreq)) != 0) { + /* Something has changed, apply the settings to HW */ + memcpy (prevChannelUpdateFreq, + actuatorSettings->ChannelUpdateFreq, + sizeof(prevChannelUpdateFreq)); + PIOS_Servo_SetHz(actuatorSettings->ChannelUpdateFreq, ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM); + } +} + +static void ActuatorSettingsUpdatedCb(UAVObjEvent * ev) +{ + actuator_settings_updated = true; +} + +static void MixerSettingsUpdatedCb(UAVObjEvent * ev) +{ + mixer_settings_updated = true; +} /** * @} diff --git a/flight/PiOS.posix/inc/pios_servo.h b/flight/PiOS.posix/inc/pios_servo.h index 7cbf37a7d..952baa5a0 100644 --- a/flight/PiOS.posix/inc/pios_servo.h +++ b/flight/PiOS.posix/inc/pios_servo.h @@ -32,7 +32,7 @@ /* Public Functions */ extern void PIOS_Servo_Init(void); -extern void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t num_banks); +extern void PIOS_Servo_SetHz(const uint16_t * speeds, uint8_t num_banks); extern void PIOS_Servo_Set(uint8_t Servo, uint16_t Position); #endif /* PIOS_SERVO_H */ diff --git a/flight/PiOS.posix/posix/pios_servo.c b/flight/PiOS.posix/posix/pios_servo.c index 93b86a1ed..d0cf530d3 100644 --- a/flight/PiOS.posix/posix/pios_servo.c +++ b/flight/PiOS.posix/posix/pios_servo.c @@ -50,7 +50,7 @@ void PIOS_Servo_Init(void) * \param[in] onetofour Rate for outputs 1 to 4 (Hz) * \param[in] fivetoeight Rate for outputs 5 to 8 (Hz) */ -void PIOS_Servo_SetHz(uint16_t * banks, uint8_t num_banks) +void PIOS_Servo_SetHz(const uint16_t * banks, uint8_t num_banks) { } diff --git a/flight/PiOS.win32/win32/pios_servo.c b/flight/PiOS.win32/win32/pios_servo.c index 93b86a1ed..d0cf530d3 100644 --- a/flight/PiOS.win32/win32/pios_servo.c +++ b/flight/PiOS.win32/win32/pios_servo.c @@ -50,7 +50,7 @@ void PIOS_Servo_Init(void) * \param[in] onetofour Rate for outputs 1 to 4 (Hz) * \param[in] fivetoeight Rate for outputs 5 to 8 (Hz) */ -void PIOS_Servo_SetHz(uint16_t * banks, uint8_t num_banks) +void PIOS_Servo_SetHz(const uint16_t * banks, uint8_t num_banks) { } diff --git a/flight/PiOS/STM32F10x/pios_servo.c b/flight/PiOS/STM32F10x/pios_servo.c index cb7d98292..46be375c2 100644 --- a/flight/PiOS/STM32F10x/pios_servo.c +++ b/flight/PiOS/STM32F10x/pios_servo.c @@ -87,7 +87,7 @@ int32_t PIOS_Servo_Init(const struct pios_servo_cfg * cfg) * \param[in] array of rates in Hz * \param[in] maximum number of banks */ -void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks) +void PIOS_Servo_SetHz(const uint16_t * speeds, uint8_t banks) { if (!servo_cfg) { return; diff --git a/flight/PiOS/STM32F4xx/pios_servo.c b/flight/PiOS/STM32F4xx/pios_servo.c index cfcf5c1e5..05188d563 100644 --- a/flight/PiOS/STM32F4xx/pios_servo.c +++ b/flight/PiOS/STM32F4xx/pios_servo.c @@ -87,7 +87,7 @@ int32_t PIOS_Servo_Init(const struct pios_servo_cfg * cfg) * \param[in] array of rates in Hz * \param[in] maximum number of banks */ -void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks) +void PIOS_Servo_SetHz(const uint16_t * speeds, uint8_t banks) { if (!servo_cfg) { return; diff --git a/flight/PiOS/inc/pios_servo.h b/flight/PiOS/inc/pios_servo.h index 043d656df..1a33149ea 100644 --- a/flight/PiOS/inc/pios_servo.h +++ b/flight/PiOS/inc/pios_servo.h @@ -31,7 +31,7 @@ #define PIOS_SERVO_H /* Public Functions */ -extern void PIOS_Servo_SetHz(uint16_t * update_rates, uint8_t channels); +extern void PIOS_Servo_SetHz(const uint16_t * update_rates, uint8_t banks); extern void PIOS_Servo_Set(uint8_t Servo, uint16_t Position); #endif /* PIOS_SERVO_H */ From 9f8d22961fa5224043fd032b0c9a13a1ae72fd55 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 11 Aug 2012 20:13:09 -0400 Subject: [PATCH 49/52] cc makefile: enable -ffunction-sections and -fdata-sections These compiler options place each function and each global variable into its own ELF section in each .o file. This, combined with the linker option --gc-sections allows the linker to evict unused functions and variables from the final ELF file. On CC, the firmware flash bank is only 118784 bytes in total. This commit reduces the .text segment from 114120 to 83536 and .data from 572 bytes to 560 bytes. That frees up a grand total of 30596 bytes of flash and 12 bytes of RAM. --- flight/CopterControl/Makefile | 1 + 1 file changed, 1 insertion(+) diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index 9acfdff41..f786df65c 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -503,6 +503,7 @@ endif CFLAGS += -Wall CFLAGS += -Werror +CFLAGS += -ffunction-sections -fdata-sections CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) # Compiler flags to generate dependency files: CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d From 4d73c1e2c2a4278171468e3a74be3501585a580f Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 11 Aug 2012 22:28:43 -0400 Subject: [PATCH 50/52] makefile: fix clobbered JTAG macro in firmware-defs.mk JTAG rules got clobbered at some point. This should fix: make fw_coptercontrol_program and others like it. --- make/firmware-defs.mk | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/make/firmware-defs.mk b/make/firmware-defs.mk index 3ead53444..522d2e320 100644 --- a/make/firmware-defs.mk +++ b/make/firmware-defs.mk @@ -210,7 +210,8 @@ endef # $(1) = Name of binary image to write # $(2) = Base of flash region to write/wipe # $(3) = Size of flash region to write/wipe -# $(4) = OpenOCD configuration file to use +# $(4) = OpenOCD JTAG interface configuration file to use +# $(5) = OpenOCD configuration file to use define JTAG_TEMPLATE # --------------------------------------------------------------------------- # Options for OpenOCD flash-programming @@ -223,7 +224,7 @@ OOCD_EXE ?= openocd OOCD_JTAG_SETUP = -d0 # interface and board/target settings (using the OOCD target-library here) OOCD_JTAG_SETUP += -s $(TOP)/flight/Project/OpenOCD -OOCD_JTAG_SETUP += -f foss-jtag.revb.cfg -f $(4) +OOCD_JTAG_SETUP += -f $(4) -f $(5) # initialize OOCD_BOARD_RESET = -c init From 63e490a922655c2cc4619c9143a0b9bc224326bc Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 12 Aug 2012 16:11:49 -0500 Subject: [PATCH 51/52] Update the config file so the mag scopes selection works --- ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml index d61dba982..af2072fe9 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml @@ -2080,7 +2080,7 @@ 4294901760 None - X + x Magnetometer 0 1 @@ -2090,7 +2090,7 @@ 4283782655 None - Y + y Magnetometer 0 1 @@ -2100,7 +2100,7 @@ 4283804160 None - Z + z Magnetometer 0 1 From 4a0d43cb54bb8566bea95ef2dca8860157139e9b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 19 Aug 2012 21:17:37 -0500 Subject: [PATCH 52/52] GCS: When PipX is detected do not make it the active configuration tab to prevent the dialog about dirty tabs appearing. Conflicts: ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp --- .../src/plugins/config/configgadgetwidget.cpp | 20 +++++++++---------- 1 file changed, 9 insertions(+), 11 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index c12dbaee8..c466df760 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -218,17 +218,15 @@ void ConfigGadgetWidget::tabAboutToChange(int i,bool * proceed) */ void ConfigGadgetWidget::updatePipXStatus(UAVObject *object) { - - // Restart the disconnection timer. - pipxTimeout->start(5000); - if (!pipxConnected) - { - qDebug()<<"ConfigGadgetWidget onPipxtremeConnect"; - QWidget *qwd = new ConfigPipXtremeWidget(this); - ftw->insertTab(ConfigGadgetWidget::pipxtreme, qwd, QIcon(":/configgadget/images/PipXtreme.png"), QString("PipXtreme")); - ftw->setCurrentIndex(ConfigGadgetWidget::pipxtreme); - pipxConnected = true; - } + // Restart the disconnection timer. + pipxTimeout->start(5000); + if (!pipxConnected) + { + qDebug()<<"ConfigGadgetWidget onPipxtremeConnect"; + QWidget *qwd = new ConfigPipXtremeWidget(this); + ftw->insertTab(ConfigGadgetWidget::pipxtreme, qwd, QIcon(":/configgadget/images/PipXtreme.png"), QString("PipXtreme")); + pipxConnected = true; + } } void ConfigGadgetWidget::onPipxtremeDisconnect() {