1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-11-30 08:24:11 +01:00

Merge remote-tracking branch 'origin/next' into laurent/OP-1337_French_translations_updates

This commit is contained in:
Laurent Lalanne 2014-05-17 10:50:47 +02:00
commit 2f3cca7478
59 changed files with 2808 additions and 1288 deletions

3
.gitignore vendored
View File

@ -24,6 +24,9 @@ core
# ground # ground
openpilotgcs-build-desktop openpilotgcs-build-desktop
ground/openpilotgcs/.cproject
ground/openpilotgcs/.project
ground/openpilotgcs/.settings
# Ignore some of the .pro.user files # Ignore some of the .pro.user files
*.pro.user *.pro.user

View File

@ -747,7 +747,7 @@ ifneq ($(strip $(filter package clean_package,$(MAKECMDGOALS))),)
# Packaged GCS should depend on opfw_resource # Packaged GCS should depend on opfw_resource
ifneq ($(strip $(filter package clean_package,$(MAKECMDGOALS))),) ifneq ($(strip $(filter package clean_package,$(MAKECMDGOALS))),)
$(eval openpilotgcs: $(OPFW_RESOURCE)) $(eval openpilotgcs_qmake: $(OPFW_RESOURCE))
endif endif
# Clean the build directory if clean_package is requested # Clean the build directory if clean_package is requested

View File

@ -254,6 +254,33 @@ static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
xSemaphoreGiveRecursive(lock); xSemaphoreGiveRecursive(lock);
return 0; return 0;
} }
/**
* Get the highest alarm severity
* @return
*/
SystemAlarmsAlarmOptions AlarmsGetHighestSeverity()
{
SystemAlarmsAlarmData alarmsData;
SystemAlarmsAlarmOptions highest = SYSTEMALARMS_ALARM_UNINITIALISED;
// Lock
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
// Read alarms
SystemAlarmsAlarmGet(&alarmsData);
// Go through alarms and find the highest severity
uint32_t n = 0;
while (n < SYSTEMALARMS_ALARM_NUMELEM && highest != SYSTEMALARMS_ALARM_CRITICAL) {
if (cast_struct_to_array(alarmsData, alarmsData.Actuator)[n] > highest) {
highest = cast_struct_to_array(alarmsData, alarmsData.Actuator)[n];
}
n++;
}
xSemaphoreGiveRecursive(lock);
return highest;
}
/** /**
* @} * @}

View File

@ -42,9 +42,11 @@ int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm);
void AlarmsDefaultAll(); void AlarmsDefaultAll();
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); int32_t AlarmsClear(SystemAlarmsAlarmElem alarm);
void AlarmsClearAll(); void AlarmsClearAll();
int32_t AlarmsHasWarnings(); int32_t AlarmsHasWarnings();
int32_t AlarmsHasErrors(); int32_t AlarmsHasErrors();
int32_t AlarmsHasCritical(); int32_t AlarmsHasCritical();
SystemAlarmsAlarmOptions AlarmsGetHighestSeverity();
#endif // ALARMS_H #endif // ALARMS_H

View File

@ -0,0 +1,38 @@
/**
******************************************************************************
*
* @file notification.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief notification library
* --
* @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 NOTIFICATION_H
#define NOTIFICATION_H
// period of each blink phase
#define LED_BLINK_PERIOD_MS 200
// update the status snapshot used by notifcations
void NotificationUpdateStatus();
// run the led notifications
void NotificationOnboardLedsRun();
#endif /* NOTIFICATION_H */

View File

@ -0,0 +1,296 @@
/**
******************************************************************************
*
* @file notification.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief notification library.
* --
* @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
*/
#include "inc/notification.h"
#include <openpilot.h>
#include <pios_struct_helper.h>
#include <systemalarms.h>
#include <flightstatus.h>
#include <pios_notify.h>
#ifdef PIOS_LED_ALARM
#define ALARM_LED_ON() PIOS_LED_On(PIOS_LED_ALARM)
#define ALARM_LED_OFF() PIOS_LED_Off(PIOS_LED_ALARM)
#else
#define ALARM_LED_ON()
#define ALARM_LED_OFF()
#endif
#ifdef PIOS_LED_HEARTBEAT
#define HEARTBEAT_LED_ON() PIOS_LED_On(PIOS_LED_HEARTBEAT)
#define HEARTBEAT_LED_OFF() PIOS_LED_Off(PIOS_LED_HEARTBEAT)
#else
#define HEARTBEAT_LED_ON()
#define HEARTBEAT_LED_OFF()
#endif
#define BLINK_R_ALARM_PATTERN(x) \
(x == SYSTEMALARMS_ALARM_OK ? 0 : \
x == SYSTEMALARMS_ALARM_WARNING ? 0b0000000001000000 : \
x == SYSTEMALARMS_ALARM_ERROR ? 0b0000001000100000 : \
x == SYSTEMALARMS_ALARM_CRITICAL ? 0b0111111111111110 : 0)
#define BLINK_B_ALARM_PATTERN(x) \
(x == SYSTEMALARMS_ALARM_OK ? 0 : \
x == SYSTEMALARMS_ALARM_WARNING ? 0 : \
x == SYSTEMALARMS_ALARM_ERROR ? 0 : \
x == SYSTEMALARMS_ALARM_CRITICAL ? 0 : 0)
#define BLINK_B_FM_ARMED_PATTERN(x) \
(x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED1 ? 0b0000000000000001 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED2 ? 0b0000000000100001 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED3 ? 0b0000010000100001 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED4 ? 0b0000000000000001 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED5 ? 0b0000000000100001 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED6 ? 0b0000010000100001 : \
x == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD ? 0b0000010000100001 : \
x == FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE ? 0b0001000100010001 : \
x == FLIGHTSTATUS_FLIGHTMODE_LAND ? 0b0001000100010001 : \
x == FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER ? 0b0000010000100001 : \
x == FLIGHTSTATUS_FLIGHTMODE_POI ? 0b0000010000100001 : 0b0000000000000001)
#define BLINK_R_FM_ARMED_PATTERN(x) \
(x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED1 ? 0b0000000000000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED2 ? 0b0000000000000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED3 ? 0b0000000000000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED4 ? 0b0000000000000001 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED5 ? 0b0000000000000001 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED6 ? 0b0000000000000001 : \
x == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD ? 0b0000010000000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE ? 0b0001000100000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_LAND ? 0b0001000100000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER ? 0b0000010000000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_POI ? 0b0000010000000000 : 0b0000010000000000)
#define BLINK_B_FM_DISARMED_PATTERN(x) \
(x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED1 ? 0b0000000000000011 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED2 ? 0b0000000001100011 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED3 ? 0b0000110001100011 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED4 ? 0b0000000000000011 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED5 ? 0b0000000001100011 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED6 ? 0b0000110001100011 : \
x == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD ? 0b0000110001100011 : \
x == FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE ? 0b0011001100110011 : \
x == FLIGHTSTATUS_FLIGHTMODE_LAND ? 0b0011001100110011 : \
x == FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER ? 0b0000110001100011 : \
x == FLIGHTSTATUS_FLIGHTMODE_POI ? 0b0000110001100011 : 0b0000000000000011)
#define BLINK_R_FM_DISARMED_PATTERN(x) \
(x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED1 ? 0b0000000000000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED2 ? 0b0000000000000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED3 ? 0b0000000000000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED4 ? 0b0000000000000011 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED5 ? 0b0000000000000011 : \
x == FLIGHTSTATUS_FLIGHTMODE_STABILIZED6 ? 0b0000000000000011 : \
x == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD ? 0b0000110000000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE ? 0b0011001100000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_LAND ? 0b0011001100000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER ? 0b0000110000000000 : \
x == FLIGHTSTATUS_FLIGHTMODE_POI ? 0b0000110000000000 : 0b0000110000000000)
#define BLINK_B_HEARTBEAT_PATTERN 0b0001111111111111
#define BLINK_R_HEARTBEAT_PATTERN 0
#define BLINK_B_NOTIFY_PATTERN(x) \
(x == NOTIFY_NONE ? 0 : \
x == NOTIFY_OK ? 0b0000100100111111 : \
x == NOTIFY_NOK ? 0b0000000000111111 : \
x == NOTIFY_DRAW_ATTENTION ? 0b0101010101010101 : 0b0101010101010101)
#define BLINK_R_NOTIFY_PATTERN(x) \
(x == NOTIFY_NONE ? 0 : \
x == NOTIFY_OK ? 0b0000000000001111 : \
x == NOTIFY_NOK ? 0b0011000011001111 : \
x == NOTIFY_DRAW_ATTENTION ? 0b1010101010101010 : 0b1010101010101010)
// led notification handling
static volatile SystemAlarmsAlarmOptions currentAlarmLevel = SYSTEMALARMS_ALARM_OK;
static volatile FlightStatusData currentFlightStatus;
static volatile bool started = false;
static volatile pios_notify_notification nextNotification = NOTIFY_NONE;
#ifdef PIOS_LED_ALARM
static bool handleAlarms(uint16_t *r_pattern, uint16_t *b_pattern);
#endif // PIOS_LED_ALARM
static bool handleNotifications(pios_notify_notification runningNotification, uint16_t *r_pattern, uint16_t *b_pattern);
static void handleFlightMode(uint16_t *r_pattern, uint16_t *b_pattern);
static void handleHeartbeat(uint16_t *r_pattern, uint16_t *b_pattern);
void NotificationUpdateStatus()
{
started = true;
// get values to be used for led handling
FlightStatusGet((FlightStatusData *)&currentFlightStatus);
currentAlarmLevel = AlarmsGetHighestSeverity();
if (nextNotification == NOTIFY_NONE) {
nextNotification = PIOS_NOTIFY_GetActiveNotification(true);
}
}
void NotificationOnboardLedsRun()
{
static portTickType lastRunTimestamp;
static uint16_t r_pattern;
static uint16_t b_pattern;
static uint8_t cycleCount; // count the number of cycles
static uint8_t lastFlightMode = -1;
static bool forceShowFlightMode = false;
static pios_notify_notification runningNotification = NOTIFY_NONE;
static enum {
STATUS_NOTIFY,
STATUS_ALARM,
STATUS_FLIGHTMODE, // flightMode/HeartBeat
STATUS_LENGHT
} status;
if (!started || (xTaskGetTickCount() - lastRunTimestamp) < (LED_BLINK_PERIOD_MS * portTICK_RATE_MS / 4)) {
return;
}
lastRunTimestamp = xTaskGetTickCount();
// the led will show various status information, subdivided in three phases
// - Notification
// - Alarm
// - Flight status
// they are shown using the above priority
// a phase last exactly 8 cycles (so bit 1<<4 is used to determine if a phase end
cycleCount++;
// Notifications are "modal" to other statuses so they takes precedence
if (status != STATUS_NOTIFY && nextNotification != NOTIFY_NONE) {
// read next notification to show
runningNotification = nextNotification;
nextNotification = NOTIFY_NONE;
// Force a notification status
status = STATUS_NOTIFY;
cycleCount = 0; // instantly start a notify cycle
} else {
if (lastFlightMode != currentFlightStatus.FlightMode) {
status = STATUS_FLIGHTMODE;
lastFlightMode = currentFlightStatus.FlightMode;
cycleCount = 0; // instantly start a flightMode cycle
forceShowFlightMode = true;
}
}
// check if a phase has just finished
if (cycleCount & 0x10) {
HEARTBEAT_LED_OFF();
ALARM_LED_OFF();
cycleCount = 0x0;
forceShowFlightMode = false;
// Notification has been just shown, cleanup
if (status == STATUS_NOTIFY) {
runningNotification = NOTIFY_NONE;
}
status = (status + 1) % STATUS_LENGHT;
}
if (status == STATUS_NOTIFY) {
if (!cycleCount && !handleNotifications(runningNotification, &r_pattern, &b_pattern)) {
// no notifications, advance
status++;
}
}
// Handles Alarm display
if (status == STATUS_ALARM) {
#ifdef PIOS_LED_ALARM
if (!cycleCount && !handleAlarms(&r_pattern, &b_pattern)) {
// no alarms, advance
status++;
}
#else
// no alarms leds, advance
status++;
#endif // PIOS_LED_ALARM
}
// **** Handles flightmode display
if (status == STATUS_FLIGHTMODE && !cycleCount) {
if (forceShowFlightMode || currentFlightStatus.Armed != FLIGHTSTATUS_ARMED_DISARMED) {
handleFlightMode(&r_pattern, &b_pattern);
} else {
handleHeartbeat(&r_pattern, &b_pattern);
}
}
// led output
if (b_pattern & 0x1) {
HEARTBEAT_LED_ON();
} else {
HEARTBEAT_LED_OFF();
}
if (r_pattern & 0x1) {
ALARM_LED_ON();
} else {
ALARM_LED_OFF();
}
r_pattern >>= 1;
b_pattern >>= 1;
}
#if defined(PIOS_LED_ALARM)
static bool handleAlarms(uint16_t *r_pattern, uint16_t *b_pattern)
{
if (currentAlarmLevel == SYSTEMALARMS_ALARM_OK) {
return false;
}
*b_pattern = BLINK_B_ALARM_PATTERN(currentAlarmLevel);
*r_pattern = BLINK_R_ALARM_PATTERN(currentAlarmLevel);
return true;
}
#endif /* PIOS_LED_ALARM */
static bool handleNotifications(pios_notify_notification runningNotification, uint16_t *r_pattern, uint16_t *b_pattern)
{
if (runningNotification == NOTIFY_NONE) {
return false;
}
*b_pattern = BLINK_B_NOTIFY_PATTERN(runningNotification);
*r_pattern = BLINK_R_NOTIFY_PATTERN(runningNotification);
return true;
}
static void handleFlightMode(uint16_t *r_pattern, uint16_t *b_pattern)
{
// Flash the heartbeat LED
uint8_t flightmode = currentFlightStatus.FlightMode;
if (currentFlightStatus.Armed == FLIGHTSTATUS_ARMED_DISARMED) {
*b_pattern = BLINK_B_FM_DISARMED_PATTERN(flightmode);
*r_pattern = BLINK_R_FM_DISARMED_PATTERN(flightmode);
} else {
*b_pattern = BLINK_B_FM_ARMED_PATTERN(flightmode);
*r_pattern = BLINK_R_FM_ARMED_PATTERN(flightmode);
}
}
static void handleHeartbeat(uint16_t *r_pattern, uint16_t *b_pattern)
{
// Flash the heartbeat LED
*b_pattern = BLINK_B_HEARTBEAT_PATTERN;
*r_pattern = BLINK_R_HEARTBEAT_PATTERN;
}

View File

@ -60,7 +60,7 @@
static xTaskHandle taskHandle; static xTaskHandle taskHandle;
static bool airspeedEnabled = false; static bool airspeedEnabled = false;
static AirspeedSettingsData airspeedSettings; static AirspeedSettingsData airspeedSettings;
static AirspeedSettingsAirspeedSensorTypeOptions lastAirspeedSensorType = 0; static AirspeedSettingsAirspeedSensorTypeOptions lastAirspeedSensorType = -1;
static int8_t airspeedADCPin = -1; static int8_t airspeedADCPin = -1;
@ -119,8 +119,6 @@ int32_t AirspeedInitialize()
} }
} }
lastAirspeedSensorType = airspeedSettings.AirspeedSensorType;
AirspeedSensorInitialize(); AirspeedSensorInitialize();
AirspeedSettingsInitialize(); AirspeedSettingsInitialize();
@ -137,17 +135,14 @@ MODULE_INITCALL(AirspeedInitialize, AirspeedStart);
static void airspeedTask(__attribute__((unused)) void *parameters) static void airspeedTask(__attribute__((unused)) void *parameters)
{ {
AirspeedSettingsUpdatedCb(AirspeedSettingsHandle()); AirspeedSettingsUpdatedCb(AirspeedSettingsHandle());
bool gpsAirspeedInitialized = false;
AirspeedSensorData airspeedData; AirspeedSensorData airspeedData;
AirspeedSensorGet(&airspeedData); AirspeedSensorGet(&airspeedData);
AirspeedSettingsUpdatedCb(NULL); AirspeedSettingsUpdatedCb(NULL);
gps_airspeedInitialize();
airspeedData.SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE; airspeedData.SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
// Main task loop // Main task loop
portTickType lastSysTime = xTaskGetTickCount(); portTickType lastSysTime = xTaskGetTickCount();
while (1) { while (1) {
@ -160,8 +155,21 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
if (airspeedSettings.AirspeedSensorType != lastAirspeedSensorType) { if (airspeedSettings.AirspeedSensorType != lastAirspeedSensorType) {
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_DEFAULT); AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_DEFAULT);
lastAirspeedSensorType = airspeedSettings.AirspeedSensorType; lastAirspeedSensorType = airspeedSettings.AirspeedSensorType;
switch (airspeedSettings.AirspeedSensorType) {
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_NONE:
// AirspeedSensor will not be updated until a different sensor is selected
// set the disconencted satus now
airspeedData.SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
AirspeedSensorSet(&airspeedData);
break;
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_GROUNDSPEEDBASEDWINDESTIMATION:
if (!gpsAirspeedInitialized) {
gpsAirspeedInitialized = true;
gps_airspeedInitialize();
}
break;
}
} }
switch (airspeedSettings.AirspeedSensorType) { switch (airspeedSettings.AirspeedSensorType) {
#if defined(PIOS_INCLUDE_MPXV) #if defined(PIOS_INCLUDE_MPXV)
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_DIYDRONESMPXV7002: case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_DIYDRONESMPXV7002:
@ -186,6 +194,10 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
gps_airspeedGet(&airspeedData, &airspeedSettings); gps_airspeedGet(&airspeedData, &airspeedSettings);
break; break;
case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_NONE: case AIRSPEEDSETTINGS_AIRSPEEDSENSORTYPE_NONE:
// no need to check so often until a sensor is enabled
AlarmsSet(SYSTEMALARMS_ALARM_AIRSPEED, SYSTEMALARMS_ALARM_DEFAULT);
vTaskDelay(2000 / portTICK_RATE_MS);
continue;
default: default:
airspeedData.SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE; airspeedData.SensorConnected = AIRSPEEDSENSOR_SENSORCONNECTED_FALSE;
break; break;

View File

@ -63,7 +63,7 @@
#include "taskinfo.h" #include "taskinfo.h"
#include "CoordinateConversions.h" #include "CoordinateConversions.h"
#include <pios_notify.h>
// Private constants // Private constants
#define STACK_SIZE_BYTES 540 #define STACK_SIZE_BYTES 540
@ -252,6 +252,7 @@ static void AttitudeTask(__attribute__((unused)) void *parameters)
rollPitchBiasRate = 0.01f; rollPitchBiasRate = 0.01f;
accel_filter_enabled = false; accel_filter_enabled = false;
init = 0; init = 0;
PIOS_NOTIFY_StartNotification(NOTIFY_DRAW_ATTENTION, NOTIFY_PRIORITY_REGULAR);
} else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) { } else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) {
accelKp = 1.0f; accelKp = 1.0f;
accelKi = 0.0f; accelKi = 0.0f;
@ -259,6 +260,7 @@ static void AttitudeTask(__attribute__((unused)) void *parameters)
rollPitchBiasRate = 0.01f; rollPitchBiasRate = 0.01f;
accel_filter_enabled = false; accel_filter_enabled = false;
init = 0; init = 0;
PIOS_NOTIFY_StartNotification(NOTIFY_DRAW_ATTENTION, NOTIFY_PRIORITY_REGULAR);
} else if (init == 0) { } else if (init == 0) {
// Reload settings (all the rates) // Reload settings (all the rates)
AttitudeSettingsAccelKiGet(&accelKi); AttitudeSettingsAccelKiGet(&accelKi);

View File

@ -63,21 +63,24 @@ static float GravityAccel(float latitude, float longitude, float altitude);
// **************** // ****************
// Private constants // Private constants
#define GPS_TIMEOUT_MS 500 #define GPS_TIMEOUT_MS 500
// delay from detecting HomeLocation.Set == False before setting new homelocation
// this prevent that a save with homelocation.Set = false triggered by gps ends saving
// the new location with Set = true.
#define GPS_HOMELOCATION_SET_DELAY 5000
#ifdef PIOS_GPS_SETS_HOMELOCATION #ifdef PIOS_GPS_SETS_HOMELOCATION
// Unfortunately need a good size stack for the WMM calculation // Unfortunately need a good size stack for the WMM calculation
#define STACK_SIZE_BYTES 1024 #define STACK_SIZE_BYTES 1024
#else #else
#if defined(PIOS_GPS_MINIMAL) #if defined(PIOS_GPS_MINIMAL)
#define STACK_SIZE_BYTES 500 #define STACK_SIZE_BYTES 500
#else #else
#define STACK_SIZE_BYTES 650 #define STACK_SIZE_BYTES 650
#endif // PIOS_GPS_MINIMAL #endif // PIOS_GPS_MINIMAL
#endif // PIOS_GPS_SETS_HOMELOCATION #endif // PIOS_GPS_SETS_HOMELOCATION
#define TASK_PRIORITY (tskIDLE_PRIORITY + 1) #define TASK_PRIORITY (tskIDLE_PRIORITY + 1)
// **************** // ****************
// Private variables // Private variables
@ -200,6 +203,9 @@ static void gpsTask(__attribute__((unused)) void *parameters)
portTickType xDelay = 100 / portTICK_RATE_MS; portTickType xDelay = 100 / portTICK_RATE_MS;
uint32_t timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS; uint32_t timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS;
#ifdef PIOS_GPS_SETS_HOMELOCATION
portTickType homelocationSetDelay = 0;
#endif
GPSPositionSensorData gpspositionsensor; GPSPositionSensorData gpspositionsensor;
GPSSettingsData gpsSettings; GPSSettingsData gpsSettings;
@ -260,7 +266,15 @@ static void gpsTask(__attribute__((unused)) void *parameters)
HomeLocationGet(&home); HomeLocationGet(&home);
if (home.Set == HOMELOCATION_SET_FALSE) { if (home.Set == HOMELOCATION_SET_FALSE) {
setHomeLocation(&gpspositionsensor); if (homelocationSetDelay == 0) {
homelocationSetDelay = xTaskGetTickCount();
}
if (xTaskGetTickCount() - homelocationSetDelay > GPS_HOMELOCATION_SET_DELAY) {
setHomeLocation(&gpspositionsensor);
homelocationSetDelay = 0;
}
} else {
homelocationSetDelay = 0;
} }
#endif #endif
} else if ((gpspositionsensor.Status == GPSPOSITIONSENSOR_STATUS_FIX3D) && } else if ((gpspositionsensor.Status == GPSPOSITIONSENSOR_STATUS_FIX3D) &&

View File

@ -274,6 +274,9 @@ static bool okToArm(void)
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1: case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2: case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3: case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED4:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6:
return true; return true;
break; break;

View File

@ -42,7 +42,7 @@
#include <revocalibration.h> #include <revocalibration.h>
#include <CoordinateConversions.h> #include <CoordinateConversions.h>
#include <pios_notify.h>
// Private constants // Private constants
#define STACK_REQUIRED 512 #define STACK_REQUIRED 512
@ -295,6 +295,7 @@ static int32_t complementaryFilter(struct data *this, float gyro[3], float accel
this->accel_filter_enabled = false; this->accel_filter_enabled = false;
this->rollPitchBiasRate = 0.01f; this->rollPitchBiasRate = 0.01f;
this->attitudeSettings.MagKp = this->magCalibrated ? 1.0f : 0.0f; this->attitudeSettings.MagKp = this->magCalibrated ? 1.0f : 0.0f;
PIOS_NOTIFY_StartNotification(NOTIFY_DRAW_ATTENTION, NOTIFY_PRIORITY_REGULAR);
} else if ((this->attitudeSettings.ZeroDuringArming == ATTITUDESETTINGS_ZERODURINGARMING_TRUE) && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) { } else if ((this->attitudeSettings.ZeroDuringArming == ATTITUDESETTINGS_ZERODURINGARMING_TRUE) && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) {
this->attitudeSettings.AccelKp = 1.0f; this->attitudeSettings.AccelKp = 1.0f;
this->attitudeSettings.AccelKi = 0.0f; this->attitudeSettings.AccelKi = 0.0f;
@ -303,6 +304,7 @@ static int32_t complementaryFilter(struct data *this, float gyro[3], float accel
this->rollPitchBiasRate = 0.01f; this->rollPitchBiasRate = 0.01f;
this->attitudeSettings.MagKp = this->magCalibrated ? 1.0f : 0.0f; this->attitudeSettings.MagKp = this->magCalibrated ? 1.0f : 0.0f;
this->init = 0; this->init = 0;
PIOS_NOTIFY_StartNotification(NOTIFY_DRAW_ATTENTION, NOTIFY_PRIORITY_REGULAR);
} else if (this->init == 0) { } else if (this->init == 0) {
// Reload settings (all the rates) // Reload settings (all the rates)
AttitudeSettingsGet(&this->attitudeSettings); AttitudeSettingsGet(&this->attitudeSettings);

View File

@ -42,7 +42,7 @@
#include <pios_struct_helper.h> #include <pios_struct_helper.h>
// private includes // private includes
#include "inc/systemmod.h" #include "inc/systemmod.h"
#include "notification.h"
// UAVOs // UAVOs
#include <objectpersistence.h> #include <objectpersistence.h>
@ -72,22 +72,15 @@
#endif #endif
// Private constants // Private constants
#define SYSTEM_UPDATE_PERIOD_MS 1000 #define SYSTEM_UPDATE_PERIOD_MS 250
#define LED_BLINK_RATE_HZ 5
#ifndef IDLE_COUNTS_PER_SEC_AT_NO_LOAD
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 995998 // calibrated by running tests/test_cpuload.c
// must be updated if the FreeRTOS or compiler
// optimisation options are changed.
#endif
#if defined(PIOS_SYSTEM_STACK_SIZE) #if defined(PIOS_SYSTEM_STACK_SIZE)
#define STACK_SIZE_BYTES PIOS_SYSTEM_STACK_SIZE #define STACK_SIZE_BYTES PIOS_SYSTEM_STACK_SIZE
#else #else
#define STACK_SIZE_BYTES 1024 #define STACK_SIZE_BYTES 1024
#endif #endif
#define TASK_PRIORITY (tskIDLE_PRIORITY + 1) #define TASK_PRIORITY (tskIDLE_PRIORITY + 1)
// Private types // Private types
@ -98,6 +91,7 @@ static enum { STACKOVERFLOW_NONE = 0, STACKOVERFLOW_WARNING = 1, STACKOVERFLOW_C
static bool mallocFailed; static bool mallocFailed;
static HwSettingsData bootHwSettings; static HwSettingsData bootHwSettings;
static struct PIOS_FLASHFS_Stats fsStats; static struct PIOS_FLASHFS_Stats fsStats;
// Private functions // Private functions
static void objectUpdatedCb(UAVObjEvent *ev); static void objectUpdatedCb(UAVObjEvent *ev);
static void hwSettingsUpdatedCb(UAVObjEvent *ev); static void hwSettingsUpdatedCb(UAVObjEvent *ev);
@ -170,8 +164,6 @@ MODULE_INITCALL(SystemModInitialize, 0);
*/ */
static void systemTask(__attribute__((unused)) void *parameters) static void systemTask(__attribute__((unused)) void *parameters)
{ {
uint8_t cycleCount = 0;
/* create all modules thread */ /* create all modules thread */
MODULE_TASKCREATE_ALL; MODULE_TASKCREATE_ALL;
@ -189,9 +181,6 @@ static void systemTask(__attribute__((unused)) void *parameters)
/* Record a successful boot */ /* Record a successful boot */
PIOS_IAP_WriteBootCount(0); PIOS_IAP_WriteBootCount(0);
#endif #endif
// Initialize vars
// Listen for SettingPersistance object updates, connect a callback function // Listen for SettingPersistance object updates, connect a callback function
ObjectPersistenceConnectQueue(objectPersistenceQueue); ObjectPersistenceConnectQueue(objectPersistenceQueue);
@ -204,13 +193,10 @@ static void systemTask(__attribute__((unused)) void *parameters)
TaskInfoData taskInfoData; TaskInfoData taskInfoData;
CallbackInfoData callbackInfoData; CallbackInfoData callbackInfoData;
#endif #endif
// Main system loop // Main system loop
while (1) { while (1) {
NotificationUpdateStatus();
// Update the system statistics // Update the system statistics
cycleCount = cycleCount > 0 ? cycleCount - 1 : 7;
// if(cycleCount == 1){
updateStats(); updateStats();
// Update the system alarms // Update the system alarms
updateSystemAlarms(); updateSystemAlarms();
@ -230,35 +216,10 @@ static void systemTask(__attribute__((unused)) void *parameters)
// } // }
#endif #endif
// } // }
// Flash the heartbeat LED
#if defined(PIOS_LED_HEARTBEAT)
uint8_t armingStatus;
FlightStatusArmedGet(&armingStatus);
if ((armingStatus == FLIGHTSTATUS_ARMED_ARMED && (cycleCount & 0x1)) ||
(armingStatus != FLIGHTSTATUS_ARMED_ARMED && (cycleCount & 0x4))) {
PIOS_LED_On(PIOS_LED_HEARTBEAT);
} else {
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
}
DEBUG_MSG("+ 0x%08x\r\n", 0xDEADBEEF);
#endif /* PIOS_LED_HEARTBEAT */
// Turn on the error LED if an alarm is set
#if defined(PIOS_LED_ALARM)
if (AlarmsHasCritical()) {
PIOS_LED_On(PIOS_LED_ALARM);
} else if ((AlarmsHasErrors() && (cycleCount & 0x1)) ||
(!AlarmsHasErrors() && AlarmsHasWarnings() && (cycleCount & 0x4))) {
PIOS_LED_On(PIOS_LED_ALARM);
} else {
PIOS_LED_Off(PIOS_LED_ALARM);
}
#endif /* PIOS_LED_ALARM */
UAVObjEvent ev; UAVObjEvent ev;
int delayTime = SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2); int delayTime = SYSTEM_UPDATE_PERIOD_MS;
#if defined(PIOS_INCLUDE_RFM22B) #if defined(PIOS_INCLUDE_RFM22B)
@ -633,7 +594,7 @@ static void updateSystemAlarms()
UAVObjClearStats(); UAVObjClearStats();
EventClearStats(); EventClearStats();
if (objStats.eventCallbackErrors > 0 || objStats.eventQueueErrors > 0 || evStats.eventErrors > 0) { if (objStats.eventCallbackErrors > 0 || objStats.eventQueueErrors > 0 || evStats.eventErrors > 0) {
AlarmsSet(SYSTEMALARMS_ALARM_EVENTSYSTEM, SYSTEMALARMS_ALARM_WARNING); AlarmsSet(SYSTEMALARMS_ALARM_EVENTSYSTEM, SYSTEMALARMS_ALARM_ERROR);
} else { } else {
AlarmsClear(SYSTEMALARMS_ALARM_EVENTSYSTEM); AlarmsClear(SYSTEMALARMS_ALARM_EVENTSYSTEM);
} }
@ -649,11 +610,12 @@ static void updateSystemAlarms()
} }
/** /**
* Called by the RTOS when the CPU is idle, used to measure the CPU idle time. * Called by the RTOS when the CPU is idle,
*/ */
void vApplicationIdleHook(void) void vApplicationIdleHook(void)
{} {
NotificationOnboardLedsRun();
}
/** /**
* Called by the RTOS when a stack overflow is detected. * Called by the RTOS when a stack overflow is detected.
*/ */

View File

@ -661,11 +661,10 @@ static void updateTelemetryStats()
flightStats.Status = FLIGHTTELEMETRYSTATS_STATUS_DISCONNECTED; flightStats.Status = FLIGHTTELEMETRYSTATS_STATUS_DISCONNECTED;
} }
// Update the telemetry alarm // TODO: check whether is there any error condition worth raising an alarm
// Disconnection is actually a normal (non)working status so it is not raising alarms anymore.
if (flightStats.Status == FLIGHTTELEMETRYSTATS_STATUS_CONNECTED) { if (flightStats.Status == FLIGHTTELEMETRYSTATS_STATUS_CONNECTED) {
AlarmsClear(SYSTEMALARMS_ALARM_TELEMETRY); AlarmsClear(SYSTEMALARMS_ALARM_TELEMETRY);
} else {
AlarmsSet(SYSTEMALARMS_ALARM_TELEMETRY, SYSTEMALARMS_ALARM_ERROR);
} }
// Update object // Update object

View File

@ -0,0 +1,49 @@
/**
******************************************************************************
*
* @file pios_notify.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief Handles user notifications.
* --
* @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
*/
#include "pios_notify.h"
static volatile pios_notify_notification currentNotification = NOTIFY_NONE;
static volatile pios_notify_priority currentPriority;
void PIOS_NOTIFY_StartNotification(pios_notify_notification notification, pios_notify_priority priority)
{
if (currentNotification == NOTIFY_NONE || currentPriority < priority) {
currentPriority = priority;
currentNotification = notification;
}
}
pios_notify_notification PIOS_NOTIFY_GetActiveNotification(bool clear)
{
pios_notify_notification ret = currentNotification;
if (clear && ret != NOTIFY_NONE) {
currentNotification = NOTIFY_NONE;
}
return ret;
}

View File

@ -0,0 +1,58 @@
/**
******************************************************************************
*
* @file pios_notify.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief Handles user notifications.
* --
* @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_NOTIFY_H_
#define PIOS_NOTIFY_H_
#include <stdbool.h>
typedef enum {
NOTIFY_NONE = 0,
NOTIFY_OK,
NOTIFY_NOK,
NOTIFY_DRAW_ATTENTION
} pios_notify_notification;
typedef enum {
NOTIFY_PRIORITY_CRITICAL = 2,
NOTIFY_PRIORITY_REGULAR = 1,
NOTIFY_PRIORITY_LOW = 0,
} pios_notify_priority;
/**
* start a new notification. If a notification is active it will be overwritten if its priority is lower than the new one.
* The new will be discarded otherwise
* @param notification kind of notification
* @param priority priority of the new notification
*/
void PIOS_NOTIFY_StartNotification(pios_notify_notification notification, pios_notify_priority priority);
/**
* retrieve any active notification
* @param clear
* @return
*/
pios_notify_notification PIOS_NOTIFY_GetActiveNotification(bool clear);
#endif /* PIOS_NOTIFY_H_ */

View File

@ -0,0 +1,147 @@
/**
******************************************************************************
*
* @file pios_ws2811.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief A driver for ws2811 rgb led controller.
* this is a plain PiOS port of the very clever solution
* implemented by Omri Iluz in the chibios driver here:
* https://github.com/omriiluz/WS2812B-LED-Driver-ChibiOS
* @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_WS2811_H_
#define PIOS_WS2811_H_
#include <stdint.h>
#include <pios_gpio.h>
#include <pios_stm32.h>
#include <pios_gpio_priv.h>
#include <stm32f4xx.h>
#include <stm32f4xx_tim.h>
#include <stm32f4xx_dma.h>
#define sign(x) ((x > 0) - (x < 0))
#define PIOS_WS2811_NUMLEDS 2
#define PIOS_WS2811_BUFFER_SIZE (((PIOS_WS2811_NUMLEDS) * 24))
#define PIOS_WS2811_MEMORYDATASIZE DMA_MemoryDataSize_HalfWord
#define PIOS_WS2811_PERIPHERALDATASIZE DMA_PeripheralDataSize_HalfWord
#define PIOS_WS2811_TIM_PERIOD 20
// Following times are keept on the lower side to accounts
// for bus contentions and irq response time
#define PIOS_WS2811_T0_HIGH_PERIOD 25 // .35us +/- 150nS
#define PIOS_WS2811_T1_HIGH_PERIOD 60 // .70us +/- 150nS
#define PIOS_WS2811_DMA_CH1_CONFIG(channel) \
{ \
.DMA_BufferSize = PIOS_WS2811_BUFFER_SIZE, \
.DMA_Channel = channel, \
.DMA_DIR = DMA_DIR_MemoryToPeripheral, \
.DMA_FIFOMode = DMA_FIFOMode_Enable, \
.DMA_FIFOThreshold = DMA_FIFOThreshold_HalfFull, \
.DMA_Memory0BaseAddr = 0, \
.DMA_MemoryBurst = DMA_MemoryBurst_INC4, \
.DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \
.DMA_MemoryInc = DMA_MemoryInc_Enable, \
.DMA_Mode = DMA_Mode_Circular, \
.DMA_PeripheralBaseAddr = 0, \
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \
.DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \
.DMA_PeripheralInc = DMA_PeripheralInc_Disable, \
.DMA_Priority = DMA_Priority_VeryHigh, }
#define PIOS_WS2811_DMA_CH2_CONFIG(channel) \
{ \
.DMA_BufferSize = 4, \
.DMA_Channel = channel, \
.DMA_DIR = DMA_DIR_MemoryToPeripheral, \
.DMA_FIFOMode = DMA_FIFOMode_Enable, \
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full, \
.DMA_Memory0BaseAddr = 0, \
.DMA_MemoryBurst = DMA_MemoryBurst_INC4, \
.DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \
.DMA_MemoryInc = DMA_MemoryInc_Enable, \
.DMA_Mode = DMA_Mode_Circular, \
.DMA_PeripheralBaseAddr = 0, \
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \
.DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \
.DMA_PeripheralInc = DMA_PeripheralInc_Disable, \
.DMA_Priority = DMA_Priority_VeryHigh, }
#define PIOS_WS2811_DMA_UPDATE_CONFIG(channel) \
{ \
.DMA_BufferSize = 4, \
.DMA_Channel = channel, \
.DMA_DIR = DMA_DIR_MemoryToPeripheral, \
.DMA_FIFOMode = DMA_FIFOMode_Enable, \
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full, \
.DMA_Memory0BaseAddr = 0, \
.DMA_MemoryBurst = DMA_MemoryBurst_INC4, \
.DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \
.DMA_MemoryInc = DMA_MemoryInc_Enable, \
.DMA_Mode = DMA_Mode_Circular, \
.DMA_PeripheralBaseAddr = 0, \
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \
.DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \
.DMA_PeripheralInc = DMA_PeripheralInc_Disable, \
.DMA_Priority = DMA_Priority_High }
typedef uint16_t ledbuf_t;
typedef struct Color Color;
struct Color {
uint8_t R;
uint8_t G;
uint8_t B;
};
struct pios_ws2811_pin_cfg {
GPIO_TypeDef *gpio;
GPIO_InitTypeDef gpioInit;
};
struct pios_ws2811_cfg {
TIM_TimeBaseInitTypeDef timerInit;
TIM_TypeDef *timer;
uint8_t timerCh1;
uint8_t timerCh2;
DMA_InitTypeDef dmaInitCh1;
DMA_Stream_TypeDef *streamCh1;
uint32_t dmaItCh1;
DMA_InitTypeDef dmaInitCh2;
DMA_Stream_TypeDef *streamCh2;
uint32_t dmaItCh2;
DMA_InitTypeDef dmaInitUpdate;
DMA_Stream_TypeDef *streamUpdate;
uint32_t dmaItUpdate;
uint16_t dmaSource;
struct stm32_irq irq;
};
void PIOS_WS2811_Init(const struct pios_ws2811_cfg *ws2811_cfg, const struct pios_ws2811_pin_cfg *ws2811_pin_cfg);
void PIOS_WS2811_setColorRGB(Color c, uint8_t led, bool update);
void PIOS_WS2811_Update();
void PIOS_WS2811_DMA_irq_handler();
#endif /* PIOS_WS2811_H_ */

View File

@ -0,0 +1,344 @@
/**
******************************************************************************
*
* @file pios_ws2811.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
* @brief A driver for ws2811 rgb led controller.
* this is a plain PiOS port of the very clever solution
* implemented by Omri Iluz in the chibios driver here:
* https://github.com/omriiluz/WS2812B-LED-Driver-ChibiOS
* @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
*/
#include <pios.h>
#ifdef PIOS_INCLUDE_WS2811
#include "pios_ws2811.h"
#include <stm32f4xx_rcc.h>
#include <pios_stm32.h>
#include "FreeRTOS.h"
#include "task.h"
// framebuffer
static ledbuf_t *fb = 0;
// bitmask with pin to be set/reset using dma
static ledbuf_t dmaSource[4];
static const struct pios_ws2811_cfg *pios_ws2811_cfg;
static const struct pios_ws2811_pin_cfg *pios_ws2811_pin_cfg;
static void setupTimer();
static void setupDMA();
// generic wrapper around corresponding SPL functions
static void genericTIM_OCxInit(TIM_TypeDef *TIMx, const TIM_OCInitTypeDef *TIM_OCInitStruct, uint8_t ch);
static void genericTIM_OCxPreloadConfig(TIM_TypeDef *TIMx, uint16_t TIM_OCPreload, uint8_t ch);
// timer creates a 1.25 uS signal, with duty cycle controlled by frame buffer values
/* Example configuration fragment for REVOLUTION
#ifdef PIOS_INCLUDE_WS2811
#include <pios_ws2811.h>
#include <hwsettings.h>
#define PIOS_WS2811_TIM_DIVIDER (PIOS_PERIPHERAL_APB2_CLOCK / (800000 * PIOS_WS2811_TIM_PERIOD))
// interrupt vector for DMA streamCh1
void DMA2_Stream1_IRQHandler(void) __attribute__((alias("PIOS_WS2811_irq_handler")));
const struct pios_ws2811_pin_cfg pios_ws2811_pin_cfg[] = {
[HWSETTINGS_WS2811LED_OUT_SERVOOUT1] = {
.gpio = GPIOB,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
....
[HWSETTINGS_WS2811LED_OUT_FLEXIPIN4] = {
.gpio = GPIOB,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_13,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
};
const struct pios_ws2811_cfg pios_ws2811_cfg = {
.timer = TIM1,
.timerInit = {
.TIM_Prescaler = PIOS_WS2811_TIM_DIVIDER - 1,
.TIM_ClockDivision = TIM_CKD_DIV1,
.TIM_CounterMode = TIM_CounterMode_Up,
// period (1.25 uS per period
.TIM_Period = PIOS_WS2811_TIM_PERIOD,
.TIM_RepetitionCounter = 0x0000,
},
.timerCh1 = 1,
.streamCh1 = DMA2_Stream1,
.timerCh2 = 3,
.streamCh2 = DMA2_Stream6,
.streamUpdate = DMA2_Stream5,
// DMA streamCh1, triggered by timerCh1 pwm signal.
// if FrameBuffer indicates, reset output value early to indicate "0" bit to ws2812
.dmaInitCh1 = PIOS_WS2811_DMA_UPDATE_CONFIG(DMA_Channel_6),
.dmaItCh1 = DMA_IT_TEIF1 | DMA_IT_TCIF1,
// DMA streamCh2, triggered by timerCh2 pwm signal.
// Reset output value late to indicate "1" bit to ws2812.
.dmaInitCh2 = PIOS_WS2811_DMA_CH1_CONFIG(DMA_Channel_6),
.dmaItCh2 = DMA_IT_TEIF6 | DMA_IT_TCIF6,
// DMA streamUpdate Triggered by timer update event
// Outputs a high logic level at beginning of a cycle
.dmaInitUpdate = PIOS_WS2811_DMA_CH2_CONFIG(DMA_Channel_6),
.dmaItUpdate = DMA_IT_TEIF5 | DMA_IT_TCIF5,
.dmaSource = TIM_DMA_CC1 | TIM_DMA_CC3 | TIM_DMA_Update,
// DMA streamCh1 interrupt vector, used to block timer at end of framebuffer transfer
.irq = {
.flags = (DMA_IT_TCIF1),
.init = {
.NVIC_IRQChannel = DMA2_Stream1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
void PIOS_WS2811_irq_handler(void)
{
PIOS_WS2811_DMA_irq_handler();
}
#endif // PIOS_INCLUDE_WS2811
*/
/*
* How it works:
* a timer and two channels will produce the timings events:
* timer period will be 1.25us
* Ch1 CC event will be raised at 0.40uS from the beginning of the cycle
* Ch2 CC event will be raised at 0.80uS from the beginning of the cycle
* At cycle init an Update event will be raised.
*
* Three dma streams will handle the output pin as following:
* - streamUpdate dma stream, triggered by update event will produce a logic 1 on the output pin
* - streamCh1 will bring the pin to 0 if framebuffer location is set to dmaSource value to send a "0" bit to WS281x
* - streamCh2 will bring pin to 0 once .8us are passed to send a "1" bit to ws281x
* Once StreamCh1 has finished to send the buffer the IRQ handler will stop the timer.
*
*/
/**
* @brief Initialize WS2811 Led Driver
* @details Initialize the Led Driver based on passed configuration
*
* @param[in] ws2811_cfg ws2811 driver configuration
* @param[in] ws2811_pin_cfg pin to be used as output
*
*/
void PIOS_WS2811_Init(const struct pios_ws2811_cfg *ws2811_cfg, const struct pios_ws2811_pin_cfg *ws2811_pin_cfg)
{
assert_param(ws2811_cfg);
assert_param(ws2811_pin_cfg);
pios_ws2811_pin_cfg = ws2811_pin_cfg;
pios_ws2811_cfg = ws2811_cfg;
GPIO_Init(pios_ws2811_pin_cfg->gpio, &pios_ws2811_pin_cfg->gpioInit);
for (uint8_t i = 0; i < 4; i++) {
dmaSource[i] = (ledbuf_t)pios_ws2811_pin_cfg->gpioInit.GPIO_Pin;
}
fb = (ledbuf_t *)pvPortMalloc(PIOS_WS2811_BUFFER_SIZE * sizeof(ledbuf_t));
memset(fb, 0, PIOS_WS2811_BUFFER_SIZE * sizeof(ledbuf_t));
Color ledoff = { 0, 0, 0 };
for (uint8_t i = 0; i < PIOS_WS2811_NUMLEDS; i++) {
PIOS_WS2811_setColorRGB(ledoff, i, false);
}
// Setup timers
setupTimer();
setupDMA();
}
void setupTimer()
{
// Stop timer
TIM_Cmd(pios_ws2811_cfg->timer, DISABLE);
// Configure timebase and internal clock
TIM_TimeBaseInit(pios_ws2811_cfg->timer, &pios_ws2811_cfg->timerInit);
TIM_InternalClockConfig(pios_ws2811_cfg->timer);
genericTIM_OCxPreloadConfig(pios_ws2811_cfg->timer, TIM_OCPreload_Enable, pios_ws2811_cfg->timerCh1);
genericTIM_OCxPreloadConfig(pios_ws2811_cfg->timer, TIM_OCPreload_Enable, pios_ws2811_cfg->timerCh2);
TIM_ARRPreloadConfig(pios_ws2811_cfg->timer, ENABLE);
// enable outputs
// TIM_CtrlPWMOutputs(pios_ws2811_cfg->timer, ENABLE);
TIM_DMACmd(pios_ws2811_cfg->timer, pios_ws2811_cfg->dmaSource, ENABLE);
TIM_OCInitTypeDef oc = {
.TIM_OCMode = TIM_OCMode_PWM1,
.TIM_OutputState = TIM_OutputState_Enable,
.TIM_OutputNState = TIM_OutputNState_Disable,
.TIM_Pulse = 0,
.TIM_OCPolarity = TIM_OCPolarity_High,
.TIM_OCNPolarity = TIM_OCNPolarity_High,
.TIM_OCIdleState = TIM_OCIdleState_Reset,
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
};
// (duty in ticks) / (period in ticks) * 1.25uS (period in S) = 0.40 uS
oc.TIM_Pulse = PIOS_WS2811_T0_HIGH_PERIOD * PIOS_WS2811_TIM_PERIOD / 125;
genericTIM_OCxInit(pios_ws2811_cfg->timer, &oc, pios_ws2811_cfg->timerCh1);
// (duty in ticks) / (period in ticks) * 1.25uS (period in S) = 0.80 uS
oc.TIM_Pulse = PIOS_WS2811_T1_HIGH_PERIOD * PIOS_WS2811_TIM_PERIOD / 125;
genericTIM_OCxInit(pios_ws2811_cfg->timer, &oc, pios_ws2811_cfg->timerCh2);
}
void genericTIM_OCxInit(TIM_TypeDef *TIMx, const TIM_OCInitTypeDef *TIM_OCInitStruct, uint8_t ch)
{
switch (ch) {
case 1:
TIM_OC1Init(TIMx, TIM_OCInitStruct);
break;
case 2:
TIM_OC2Init(TIMx, TIM_OCInitStruct);
break;
case 3:
TIM_OC3Init(TIMx, TIM_OCInitStruct);
break;
case 4:
TIM_OC4Init(TIMx, TIM_OCInitStruct);
break;
}
}
void genericTIM_OCxPreloadConfig(TIM_TypeDef *TIMx, uint16_t TIM_OCPreload, uint8_t ch)
{
switch (ch) {
case 1:
TIM_OC1PreloadConfig(TIMx, TIM_OCPreload);
break;
case 2:
TIM_OC2PreloadConfig(TIMx, TIM_OCPreload);
break;
case 3:
TIM_OC3PreloadConfig(TIMx, TIM_OCPreload);
break;
case 4:
TIM_OC4PreloadConfig(TIMx, TIM_OCPreload);
break;
}
}
void setupDMA()
{
// Configure Ch1
DMA_Init(pios_ws2811_cfg->streamCh1, (DMA_InitTypeDef *)&pios_ws2811_cfg->dmaInitCh1);
pios_ws2811_cfg->streamCh1->PAR = (uint32_t)&pios_ws2811_pin_cfg->gpio->BSRRH;
pios_ws2811_cfg->streamCh1->M0AR = (uint32_t)fb;
NVIC_Init((NVIC_InitTypeDef *)&(pios_ws2811_cfg->irq.init));
DMA_ITConfig(pios_ws2811_cfg->streamCh1, DMA_IT_TC, ENABLE);
DMA_Init(pios_ws2811_cfg->streamCh2, (DMA_InitTypeDef *)&pios_ws2811_cfg->dmaInitCh2);
pios_ws2811_cfg->streamCh2->PAR = (uint32_t)&pios_ws2811_pin_cfg->gpio->BSRRH;
pios_ws2811_cfg->streamCh2->M0AR = (uint32_t)dmaSource;
DMA_Init(pios_ws2811_cfg->streamUpdate, (DMA_InitTypeDef *)&pios_ws2811_cfg->dmaInitUpdate);
pios_ws2811_cfg->streamUpdate->PAR = (uint32_t)&pios_ws2811_pin_cfg->gpio->BSRRL;
pios_ws2811_cfg->streamUpdate->M0AR = (uint32_t)dmaSource;
DMA_ClearITPendingBit(pios_ws2811_cfg->streamCh1, pios_ws2811_cfg->dmaItCh1);
DMA_ClearITPendingBit(pios_ws2811_cfg->streamCh2, pios_ws2811_cfg->dmaItCh2);
DMA_ClearITPendingBit(pios_ws2811_cfg->streamUpdate, pios_ws2811_cfg->dmaItUpdate);
DMA_Cmd(pios_ws2811_cfg->streamCh2, ENABLE);
DMA_Cmd(pios_ws2811_cfg->streamCh1, ENABLE);
DMA_Cmd(pios_ws2811_cfg->streamUpdate, ENABLE);
}
void setColor(uint8_t color, ledbuf_t *buf)
{
uint8_t i;
for (i = 0; i < 8; i++) {
buf[i] = ((color << i) & 0b10000000 ? 0x0 : dmaSource[0]);
}
}
/**
* Set a led color
* @param c color
* @param led led number
* @param update Perform an update after changing led color
*/
void PIOS_WS2811_setColorRGB(Color c, uint8_t led, bool update)
{
if (led >= PIOS_WS2811_NUMLEDS) {
return;
}
setColor(c.G, fb + (led * 24));
setColor(c.R, fb + 8 + (led * 24));
setColor(c.B, fb + 16 + (led * 24));
if (update) {
PIOS_WS2811_Update();
}
}
/**
* trigger an update cycle if not already running
*/
void PIOS_WS2811_Update()
{
// does not start if framebuffer is not allocated (init has not been called yet) or a transfer is still on going
if (!fb || (pios_ws2811_cfg->timer->CR1 & TIM_CR1_CEN)) {
return;
}
// reset counters for synchronization
pios_ws2811_cfg->timer->CNT = PIOS_WS2811_TIM_PERIOD - 1;
// Start a new cycle
TIM_Cmd(pios_ws2811_cfg->timer, ENABLE);
}
/**
* Stop timer once the complete framebuffer has been sent
*/
void PIOS_WS2811_DMA_irq_handler()
{
pios_ws2811_cfg->timer->CR1 &= (uint16_t) ~TIM_CR1_CEN;
DMA_ClearFlag(pios_ws2811_cfg->streamCh1, pios_ws2811_cfg->irq.flags);
}
#endif // PIOS_INCLUDE_WS2811

View File

@ -48,9 +48,13 @@ OPTMODULES += Osd/osdoutput
#OPTMODULES += Altitude #OPTMODULES += Altitude
#OPTMODULES += Fault #OPTMODULES += Fault
SRC += $(FLIGHTLIB)/notification.c
# Include all camera options # Include all camera options
CDEFS += -DUSE_INPUT_LPF -DUSE_GIMBAL_LPF -DUSE_GIMBAL_FF CDEFS += -DUSE_INPUT_LPF -DUSE_GIMBAL_LPF -DUSE_GIMBAL_FF
# Erase flash firmware should be buildable from command line # Erase flash firmware should be buildable from command line
ifeq ($(ERASE_FLASH), YES) ifeq ($(ERASE_FLASH), YES)
CDEFS += -DERASE_FLASH CDEFS += -DERASE_FLASH

View File

@ -1810,3 +1810,69 @@ const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
.data_tx_ep = 1, .data_tx_ep = 1,
}; };
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */ #endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */
#ifdef PIOS_INCLUDE_WS2811
#include <pios_ws2811.h>
#define PIOS_WS2811_TIM_DIVIDER (PIOS_PERIPHERAL_APB2_CLOCK / (800000 * PIOS_WS2811_TIM_PERIOD))
void DMA2_Stream1_IRQHandler(void) __attribute__((alias("PIOS_WS2811_irq_handler")));
const struct pios_ws2811_pin_cfg pios_ws2811_pin_cfg = {
.gpio = GPIOA,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_3,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
};
const struct pios_ws2811_cfg pios_ws2811_cfg = {
.timer = TIM1,
.timerInit = {
.TIM_Prescaler = PIOS_WS2811_TIM_DIVIDER - 1,
.TIM_ClockDivision = TIM_CKD_DIV1,
.TIM_CounterMode = TIM_CounterMode_Up,
// period (1.25 uS per period
.TIM_Period = PIOS_WS2811_TIM_PERIOD,
.TIM_RepetitionCounter = 0x0000,
},
.timerCh1 = 1,
.streamCh1 = DMA2_Stream1,
.timerCh2 = 3,
.streamCh2 = DMA2_Stream6,
.streamUpdate = DMA2_Stream5,
// DMA streamCh1, triggered by timerCh1 pwm signal.
// if FrameBuffer indicates, reset output value early to indicate "0" bit to ws2812
.dmaInitCh1 = PIOS_WS2811_DMA_CH1_CONFIG(DMA_Channel_6),
.dmaItCh1 = DMA_IT_TEIF1 | DMA_IT_TCIF1,
// DMA streamCh2, triggered by timerCh2 pwm signal.
// Reset output value late to indicate "1" bit to ws2812.
.dmaInitCh2 = PIOS_WS2811_DMA_CH2_CONFIG(DMA_Channel_6),
.dmaItCh2 = DMA_IT_TEIF6 | DMA_IT_TCIF6,
// DMA streamUpdate Triggered by timer update event
// Outputs a high logic level at beginning of a cycle
.dmaInitUpdate = PIOS_WS2811_DMA_UPDATE_CONFIG(DMA_Channel_6),
.dmaItUpdate = DMA_IT_TEIF5 | DMA_IT_TCIF5,
.dmaSource = TIM_DMA_CC1 | TIM_DMA_CC3 | TIM_DMA_Update,
// DMA streamCh1 interrupt vector, used to block timer at end of framebuffer transfer
.irq = {
.flags = (DMA_IT_TCIF1),
.init = {
.NVIC_IRQChannel = DMA2_Stream1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
void PIOS_WS2811_irq_handler(void)
{
PIOS_WS2811_DMA_irq_handler();
}
#endif // PIOS_INCLUDE_WS2811

View File

@ -52,6 +52,8 @@ MODULES += Telemetry
OPTMODULES += ComUsbBridge OPTMODULES += ComUsbBridge
SRC += $(FLIGHTLIB)/notification.c
# Include all camera options # Include all camera options
CDEFS += -DUSE_INPUT_LPF -DUSE_GIMBAL_LPF -DUSE_GIMBAL_FF CDEFS += -DUSE_INPUT_LPF -DUSE_GIMBAL_LPF -DUSE_GIMBAL_FF

View File

@ -88,6 +88,7 @@
// #define PIOS_INCLUDE_MPXV // #define PIOS_INCLUDE_MPXV
// #define PIOS_INCLUDE_ETASV3 // #define PIOS_INCLUDE_ETASV3
/* #define PIOS_INCLUDE_HCSR04 */ /* #define PIOS_INCLUDE_HCSR04 */
#define PIOS_INCLUDE_WS2811
/* PIOS receiver drivers */ /* PIOS receiver drivers */
#define PIOS_INCLUDE_PWM #define PIOS_INCLUDE_PWM

View File

@ -36,7 +36,6 @@
#include <pios_oplinkrcvr_priv.h> #include <pios_oplinkrcvr_priv.h>
#include <taskinfo.h> #include <taskinfo.h>
#include <pios_callbackscheduler.h> #include <pios_callbackscheduler.h>
/* /*
* Pull in the board-specific static HW definitions. * Pull in the board-specific static HW definitions.
* Including .c files is a bit ugly but this allows all of * Including .c files is a bit ugly but this allows all of
@ -932,6 +931,11 @@ void PIOS_Board_Init(void)
PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg); PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg);
PIOS_MPU6000_CONFIG_Configure(); PIOS_MPU6000_CONFIG_Configure();
#endif #endif
#ifdef PIOS_INCLUDE_WS2811
#include <pios_ws2811.h>
PIOS_WS2811_Init(&pios_ws2811_cfg, &pios_ws2811_pin_cfg);
#endif // PIOS_INCLUDE_WS2811
} }
/** /**

View File

@ -37,6 +37,8 @@ MODULES += Telemetry
OPTMODULES = OPTMODULES =
SRC += $(FLIGHTLIB)/notification.c
# Some diagnostics # Some diagnostics
CDEFS += -DDIAG_TASKS CDEFS += -DDIAG_TASKS

View File

@ -1962,3 +1962,138 @@ const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
.data_tx_ep = 1, .data_tx_ep = 1,
}; };
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */ #endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */
#ifdef PIOS_INCLUDE_WS2811
#include <pios_ws2811.h>
#include <hwsettings.h>
#define PIOS_WS2811_TIM_DIVIDER (PIOS_PERIPHERAL_APB2_CLOCK / (800000 * PIOS_WS2811_TIM_PERIOD))
void DMA2_Stream1_IRQHandler(void) __attribute__((alias("PIOS_WS2811_irq_handler")));
// list of pin configurable as ws281x outputs.
// this will not clash with PWM in or servo output as
// pins will be reconfigured as _OUT so the alternate function is disabled.
const struct pios_ws2811_pin_cfg pios_ws2811_pin_cfg[] = {
[HWSETTINGS_WS2811LED_OUT_SERVOOUT1] = {
.gpio = GPIOB,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_SERVOOUT2] = {
.gpio = GPIOB,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_SERVOOUT3] = {
.gpio = GPIOA,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_3,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_SERVOOUT4] = {
.gpio = GPIOA,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_2,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_SERVOOUT5] = {
.gpio = GPIOA,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_SERVOOUT6] = {
.gpio = GPIOA,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_FLEXIPIN3] = {
.gpio = GPIOB,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_12,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_FLEXIPIN4] = {
.gpio = GPIOB,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_13,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
};
const struct pios_ws2811_cfg pios_ws2811_cfg = {
.timer = TIM1,
.timerInit = {
.TIM_Prescaler = PIOS_WS2811_TIM_DIVIDER - 1,
.TIM_ClockDivision = TIM_CKD_DIV1,
.TIM_CounterMode = TIM_CounterMode_Up,
// period (1.25 uS per period
.TIM_Period = PIOS_WS2811_TIM_PERIOD,
.TIM_RepetitionCounter = 0x0000,
},
.timerCh1 = 1,
.streamCh1 = DMA2_Stream1,
.timerCh2 = 3,
.streamCh2 = DMA2_Stream6,
.streamUpdate = DMA2_Stream5,
// DMA streamCh1, triggered by timerCh1 pwm signal.
// if FrameBuffer indicates, reset output value early to indicate "0" bit to ws2812
.dmaInitCh1 = PIOS_WS2811_DMA_CH1_CONFIG(DMA_Channel_6),
.dmaItCh1 = DMA_IT_TEIF1 | DMA_IT_TCIF1,
// DMA streamCh2, triggered by timerCh2 pwm signal.
// Reset output value late to indicate "1" bit to ws2812.
.dmaInitCh2 = PIOS_WS2811_DMA_CH2_CONFIG(DMA_Channel_6),
.dmaItCh2 = DMA_IT_TEIF6 | DMA_IT_TCIF6,
// DMA streamUpdate Triggered by timer update event
// Outputs a high logic level at beginning of a cycle
.dmaInitUpdate = PIOS_WS2811_DMA_UPDATE_CONFIG(DMA_Channel_6),
.dmaItUpdate = DMA_IT_TEIF5 | DMA_IT_TCIF5,
.dmaSource = TIM_DMA_CC1 | TIM_DMA_CC3 | TIM_DMA_Update,
// DMAInitCh1 interrupt vector, used to block timer at end of framebuffer transfer
.irq = {
.flags = (DMA_IT_TCIF1),
.init = {
.NVIC_IRQChannel = DMA2_Stream1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
void PIOS_WS2811_irq_handler(void)
{
PIOS_WS2811_DMA_irq_handler();
}
#endif // PIOS_INCLUDE_WS2811

View File

@ -53,6 +53,8 @@ MODULES += Telemetry
OPTMODULES += ComUsbBridge OPTMODULES += ComUsbBridge
SRC += $(FLIGHTLIB)/notification.c
# Include all camera options # Include all camera options
CDEFS += -DUSE_INPUT_LPF -DUSE_GIMBAL_LPF -DUSE_GIMBAL_FF CDEFS += -DUSE_INPUT_LPF -DUSE_GIMBAL_LPF -DUSE_GIMBAL_FF
@ -96,7 +98,9 @@ endif
# Optional component libraries # Optional component libraries
include $(FLIGHTLIB)/rscode/library.mk include $(FLIGHTLIB)/rscode/library.mk
#include $(FLIGHTLIB)/PyMite/pymite.mk #include $(FLIGHTLIB)/PyMite/pymite.mk
include $(ROOT_DIR)/make/apps-defs.mk include $(ROOT_DIR)/make/apps-defs.mk
include $(ROOT_DIR)/make/common-defs.mk include $(ROOT_DIR)/make/common-defs.mk

View File

@ -89,6 +89,8 @@
#define PIOS_INCLUDE_ETASV3 #define PIOS_INCLUDE_ETASV3
#define PIOS_INCLUDE_MS4525DO #define PIOS_INCLUDE_MS4525DO
#define PIOS_INCLUDE_WS2811
/* #define PIOS_INCLUDE_HCSR04 */ /* #define PIOS_INCLUDE_HCSR04 */
/* PIOS receiver drivers */ /* PIOS receiver drivers */

View File

@ -35,6 +35,7 @@
#include <oplinkreceiver.h> #include <oplinkreceiver.h>
#include <pios_oplinkrcvr_priv.h> #include <pios_oplinkrcvr_priv.h>
#include <taskinfo.h> #include <taskinfo.h>
#include <pios_ws2811.h>
/* /*
* Pull in the board-specific static HW definitions. * Pull in the board-specific static HW definitions.
@ -945,6 +946,17 @@ void PIOS_Board_Init(void)
PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg); PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg);
PIOS_MPU6000_CONFIG_Configure(); PIOS_MPU6000_CONFIG_Configure();
#endif #endif
#ifdef PIOS_INCLUDE_WS2811
#include <pios_ws2811.h>
HwSettingsWS2811LED_OutOptions ws2811_pin_settings;
HwSettingsWS2811LED_OutGet(&ws2811_pin_settings);
if (ws2811_pin_settings != HWSETTINGS_WS2811LED_OUT_DISABLED && ws2811_pin_settings < NELEMENTS(pios_ws2811_pin_cfg)) {
PIOS_WS2811_Init(&pios_ws2811_cfg, &pios_ws2811_pin_cfg[ws2811_pin_settings]);
}
#endif // PIOS_INCLUDE_WS2811
} }
/** /**

View File

@ -50,6 +50,8 @@ MODULES += Osd/osdoutout
MODULES += Logging MODULES += Logging
MODULES += Telemetry MODULES += Telemetry
SRC += $(FLIGHTLIB)/notification.c
OPTMODULES += ComUsbBridge OPTMODULES += ComUsbBridge
# Include all camera options # Include all camera options

View File

@ -45,6 +45,8 @@ MODULES += Airspeed
#MODULES += AltitudeHold # now integrated in Stabilization #MODULES += AltitudeHold # now integrated in Stabilization
#MODULES += OveroSync #MODULES += OveroSync
SRC += $(FLIGHTLIB)/notification.c
# Paths # Paths
OPSYSTEM = . OPSYSTEM = .
BOARDINC = .. BOARDINC = ..
@ -103,6 +105,8 @@ SRC += $(PIOSCORECOMMON)/pios_dosfs_logfs.c
SRC += $(PIOSCORECOMMON)/pios_debuglog.c SRC += $(PIOSCORECOMMON)/pios_debuglog.c
SRC += $(PIOSCORECOMMON)/pios_callbackscheduler.c SRC += $(PIOSCORECOMMON)/pios_callbackscheduler.c
SRC += $(PIOSCORECOMMON)/pios_deltatime.c SRC += $(PIOSCORECOMMON)/pios_deltatime.c
SRC += $(PIOSCORECOMMON)/pios_notify.c
## PIOS Hardware ## PIOS Hardware
include $(PIOS)/posix/library.mk include $(PIOS)/posix/library.mk

View File

@ -82,13 +82,34 @@ MyTabbedStackWidget::MyTabbedStackWidget(QWidget *parent, bool isVertical, bool
void MyTabbedStackWidget::insertTab(const int index, QWidget *tab, const QIcon &icon, const QString &label) void MyTabbedStackWidget::insertTab(const int index, QWidget *tab, const QIcon &icon, const QString &label)
{ {
tab->setContentsMargins(0, 0, 0, 0); // create and insert item
m_stackWidget->insertWidget(index, tab);
QListWidgetItem *item = new QListWidgetItem(icon, label); QListWidgetItem *item = new QListWidgetItem(icon, label);
item->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable); item->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
item->setTextAlignment(Qt::AlignHCenter | Qt::AlignBottom); item->setTextAlignment(Qt::AlignHCenter | Qt::AlignBottom);
item->setToolTip(label); item->setToolTip(label);
m_listWidget->insertItem(index, item); m_listWidget->insertItem(index, item);
// setup and insert widget
tab->setContentsMargins(0, 0, 0, 0);
m_stackWidget->insertWidget(index, tab);
}
void MyTabbedStackWidget::replaceTab(int index, QWidget *tab)
{
QWidget *wid = m_stackWidget->widget(index);
// setup and insert new widget
tab->setContentsMargins(0, 0, 0, 0);
m_stackWidget->insertWidget(index, tab);
// check special case when replacing currenlty selected tab
if (index == currentIndex()) {
// currently selected tab is being replaced so select the new tab before removing the old one
m_stackWidget->setCurrentWidget(tab);
}
// remove and delete old widget
m_stackWidget->removeWidget(wid);
delete wid;
} }
void MyTabbedStackWidget::removeTab(int index) void MyTabbedStackWidget::removeTab(int index)
@ -97,6 +118,7 @@ void MyTabbedStackWidget::removeTab(int index)
m_stackWidget->removeWidget(wid); m_stackWidget->removeWidget(wid);
delete wid; delete wid;
QListWidgetItem *item = m_listWidget->item(index); QListWidgetItem *item = m_listWidget->item(index);
m_listWidget->removeItemWidget(item); m_listWidget->removeItemWidget(item);
delete item; delete item;

View File

@ -40,6 +40,7 @@ public:
MyTabbedStackWidget(QWidget *parent = 0, bool isVertical = false, bool iconAbove = true); MyTabbedStackWidget(QWidget *parent = 0, bool isVertical = false, bool iconAbove = true);
void insertTab(int index, QWidget *tab, const QIcon &icon, const QString &label); void insertTab(int index, QWidget *tab, const QIcon &icon, const QString &label);
void replaceTab(int index, QWidget *tab);
void removeTab(int index); void removeTab(int index);
void setIconSize(int size) void setIconSize(int size)
{ {

View File

@ -0,0 +1,73 @@
#include "channelform.h"
#include <QGridLayout>
ChannelForm::ChannelForm(const int index, QWidget *parent) : ConfigTaskWidget(parent), m_index(index)
{}
ChannelForm::~ChannelForm()
{}
int ChannelForm::index() const
{
return m_index;
}
void ChannelForm::moveTo(QGridLayout &dstLayout)
{
QGridLayout *srcLayout = dynamic_cast<QGridLayout *>(layout());
Q_ASSERT(srcLayout);
// if we are the first row to be inserted then show the legend
bool showLegend = (dstLayout.rowCount() == 1);
if (showLegend) {
// move legend row to target grid layout
moveRow(0, *srcLayout, dstLayout);
} else {
removeRow(0, *srcLayout);
}
// move field row to target grid layout
moveRow(1, *srcLayout, dstLayout);
// this form is now empty so hide it
setVisible(false);
}
void ChannelForm::moveRow(int row, QGridLayout &srcLayout, QGridLayout &dstLayout)
{
int dstRow = dstLayout.rowCount();
for (int col = 0; col < srcLayout.columnCount(); col++) {
QLayoutItem *item = srcLayout.itemAtPosition(row, col);
if (!item) {
continue;
}
QWidget *widget = item->widget();
if (widget) {
dstLayout.addWidget(widget, dstRow, col);
continue;
}
// TODO handle item of type QLayout
}
}
void ChannelForm::removeRow(int row, QGridLayout &layout)
{
for (int col = 0; col < layout.columnCount(); col++) {
QLayoutItem *item = layout.itemAtPosition(row, col);
if (!item) {
continue;
}
QWidget *widget = item->widget();
if (widget) {
layout.removeWidget(widget);
delete widget;
continue;
}
// TODO handle item of type QLayout
}
}

View File

@ -0,0 +1,36 @@
#ifndef CHANNELFORM_H
#define CHANNELFORM_H
#include "configtaskwidget.h"
#include <QWidget>
namespace Ui {
class ChannelForm;
}
class QGridLayout;
class ChannelForm : public ConfigTaskWidget {
Q_OBJECT
public:
explicit ChannelForm(const int index, QWidget *parent = 0);
~ChannelForm();
int index() const;
virtual QString name() = 0;
virtual void setName(const QString &name) = 0;
void moveTo(QGridLayout &dstLayout);
private:
// Channel index
int m_index;
static void moveRow(int row, QGridLayout &srcLayout, QGridLayout &dstLayout);
static void removeRow(int row, QGridLayout &layout);
};
#endif // CHANNELFORM_H

View File

@ -1,18 +1,19 @@
TEMPLATE = lib TEMPLATE = lib
TARGET = Config TARGET = Config
DEFINES += CONFIG_LIBRARY DEFINES += CONFIG_LIBRARY
QT += svg
QT += opengl QT += svg opengl qml quick
QT += qml quick
include(config_dependencies.pri) include(config_dependencies.pri)
INCLUDEPATH += ../../libs/eigen INCLUDEPATH += ../../libs/eigen
OTHER_FILES += Config.pluginspec \ OTHER_FILES += \
Config.pluginspec \
calibration/WizardStepIndicator.qml calibration/WizardStepIndicator.qml
HEADERS += configplugin.h \ HEADERS += \
configplugin.h \
configgadgetwidget.h \ configgadgetwidget.h \
configgadgetfactory.h \ configgadgetfactory.h \
configgadget.h \ configgadget.h \
@ -27,6 +28,7 @@ HEADERS += configplugin.h \
assertions.h \ assertions.h \
defaultattitudewidget.h \ defaultattitudewidget.h \
defaulthwsettingswidget.h \ defaulthwsettingswidget.h \
channelform.h \
inputchannelform.h \ inputchannelform.h \
configcamerastabilizationwidget.h \ configcamerastabilizationwidget.h \
configtxpidwidget.h \ configtxpidwidget.h \
@ -57,7 +59,8 @@ HEADERS += configplugin.h \
calibration/gyrobiascalibrationmodel.h \ calibration/gyrobiascalibrationmodel.h \
calibration/calibrationuiutils.h calibration/calibrationuiutils.h
SOURCES += configplugin.cpp \ SOURCES += \
configplugin.cpp \
configgadgetwidget.cpp \ configgadgetwidget.cpp \
configgadgetfactory.cpp \ configgadgetfactory.cpp \
configgadget.cpp \ configgadget.cpp \
@ -71,6 +74,7 @@ SOURCES += configplugin.cpp \
configpipxtremewidget.cpp \ configpipxtremewidget.cpp \
defaultattitudewidget.cpp \ defaultattitudewidget.cpp \
defaulthwsettingswidget.cpp \ defaulthwsettingswidget.cpp \
channelform.cpp \
inputchannelform.cpp \ inputchannelform.cpp \
configcamerastabilizationwidget.cpp \ configcamerastabilizationwidget.cpp \
configrevowidget.cpp \ configrevowidget.cpp \
@ -95,7 +99,8 @@ SOURCES += configplugin.cpp \
calibration/levelcalibrationmodel.cpp \ calibration/levelcalibrationmodel.cpp \
calibration/gyrobiascalibrationmodel.cpp calibration/gyrobiascalibrationmodel.cpp
FORMS += airframe.ui \ FORMS += \
airframe.ui \
airframe_ccpm.ui \ airframe_ccpm.ui \
airframe_fixedwing.ui \ airframe_fixedwing.ui \
airframe_ground.ui \ airframe_ground.ui \

View File

@ -55,69 +55,67 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
{ {
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
ftw = new MyTabbedStackWidget(this, true, true); stackWidget = new MyTabbedStackWidget(this, true, true);
ftw->setIconSize(64); stackWidget->setIconSize(64);
QVBoxLayout *layout = new QVBoxLayout; QVBoxLayout *layout = new QVBoxLayout;
layout->setContentsMargins(0, 0, 0, 0); layout->setContentsMargins(0, 0, 0, 0);
layout->addWidget(ftw); layout->addWidget(stackWidget);
setLayout(layout); setLayout(layout);
// *********************
QWidget *qwd; QWidget *qwd;
QIcon *icon = new QIcon(); QIcon *icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new DefaultHwSettingsWidget(this); qwd = new DefaultHwSettingsWidget(this);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); stackWidget->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/vehicle_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/vehicle_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/vehicle_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/vehicle_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigVehicleTypeWidget(this); qwd = new ConfigVehicleTypeWidget(this);
ftw->insertTab(ConfigGadgetWidget::aircraft, qwd, *icon, QString("Vehicle")); stackWidget->insertTab(ConfigGadgetWidget::aircraft, qwd, *icon, QString("Vehicle"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/input_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/input_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/input_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/input_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigInputWidget(this); qwd = new ConfigInputWidget(this);
ftw->insertTab(ConfigGadgetWidget::input, qwd, *icon, QString("Input")); stackWidget->insertTab(ConfigGadgetWidget::input, qwd, *icon, QString("Input"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/output_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/output_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/output_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/output_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigOutputWidget(this); qwd = new ConfigOutputWidget(this);
ftw->insertTab(ConfigGadgetWidget::output, qwd, *icon, QString("Output")); stackWidget->insertTab(ConfigGadgetWidget::output, qwd, *icon, QString("Output"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new DefaultAttitudeWidget(this); qwd = new DefaultAttitudeWidget(this);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude")); stackWidget->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/stabilization_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/stabilization_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigStabilizationWidget(this); qwd = new ConfigStabilizationWidget(this);
ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, *icon, QString("Stabilization")); stackWidget->insertTab(ConfigGadgetWidget::stabilization, qwd, *icon, QString("Stabilization"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigCameraStabilizationWidget(this); qwd = new ConfigCameraStabilizationWidget(this);
ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Gimbal")); stackWidget->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Gimbal"));
icon = new QIcon(); icon = new QIcon();
icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off); icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/txpid_selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/txpid_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigTxPIDWidget(this); qwd = new ConfigTxPIDWidget(this);
ftw->insertTab(ConfigGadgetWidget::txpid, qwd, *icon, QString("TxPID")); stackWidget->insertTab(ConfigGadgetWidget::txpid, qwd, *icon, QString("TxPID"));
stackWidget->setCurrentIndex(ConfigGadgetWidget::hardware);
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
// *********************
// Listen to autopilot connection events // Listen to autopilot connection events
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
TelemetryManager *telMngr = pm->getObject<TelemetryManager>(); TelemetryManager *telMngr = pm->getObject<TelemetryManager>();
connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect())); connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()));
@ -129,9 +127,9 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
} }
help = 0; help = 0;
connect(ftw, SIGNAL(currentAboutToShow(int, bool *)), this, SLOT(tabAboutToChange(int, bool *))); connect(stackWidget, SIGNAL(currentAboutToShow(int, bool *)), this, SLOT(tabAboutToChange(int, bool *)));
// Connect to the PipXStatus object updates // Connect to the OPLinkStatus object updates
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>(); UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
oplinkStatusObj = dynamic_cast<UAVDataObject *>(objManager->getObject("OPLinkStatus")); oplinkStatusObj = dynamic_cast<UAVDataObject *>(objManager->getObject("OPLinkStatus"));
if (oplinkStatusObj != NULL) { if (oplinkStatusObj != NULL) {
@ -148,13 +146,13 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
ConfigGadgetWidget::~ConfigGadgetWidget() ConfigGadgetWidget::~ConfigGadgetWidget()
{ {
// TODO: properly delete all the tabs in ftw before exiting delete stackWidget;
} }
void ConfigGadgetWidget::startInputWizard() void ConfigGadgetWidget::startInputWizard()
{ {
ftw->setCurrentIndex(ConfigGadgetWidget::input); stackWidget->setCurrentIndex(ConfigGadgetWidget::input);
ConfigInputWidget *inputWidget = dynamic_cast<ConfigInputWidget *>(ftw->getWidget(ConfigGadgetWidget::input)); ConfigInputWidget *inputWidget = dynamic_cast<ConfigInputWidget *>(stackWidget->getWidget(ConfigGadgetWidget::input));
Q_ASSERT(inputWidget); Q_ASSERT(inputWidget);
inputWidget->startInputWizard(); inputWidget->startInputWizard();
} }
@ -166,24 +164,12 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event)
void ConfigGadgetWidget::onAutopilotDisconnect() void ConfigGadgetWidget::onAutopilotDisconnect()
{ {
int selectedIndex = ftw->currentIndex();
QIcon *icon = new QIcon();
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new DefaultAttitudeWidget(this); QWidget *qwd = new DefaultAttitudeWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd);
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new DefaultHwSettingsWidget(this);
ftw->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
ftw->setCurrentIndex(selectedIndex); qwd = new DefaultHwSettingsWidget(this);
stackWidget->replaceTab(ConfigGadgetWidget::hardware, qwd);
emit autopilotDisconnected(); emit autopilotDisconnected();
} }
@ -196,45 +182,25 @@ void ConfigGadgetWidget::onAutopilotConnect()
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>(); UAVObjectUtilManager *utilMngr = pm->getObject<UAVObjectUtilManager>();
if (utilMngr) { if (utilMngr) {
int selectedIndex = ftw->currentIndex();
int board = utilMngr->getBoardModel(); int board = utilMngr->getBoardModel();
if ((board & 0xff00) == 1024) { if ((board & 0xff00) == 1024) {
// CopterControl family // CopterControl family
QIcon *icon = new QIcon();
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigCCAttitudeWidget(this); QWidget *qwd = new ConfigCCAttitudeWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors); stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); qwd = new ConfigCCHWWidget(this);
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); stackWidget->replaceTab(ConfigGadgetWidget::hardware, qwd);
icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigCCHWWidget(this);
ftw->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
} else if ((board & 0xff00) == 0x0900) { } else if ((board & 0xff00) == 0x0900) {
// Revolution family // Revolution family
QIcon *icon = new QIcon();
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigRevoWidget(this); QWidget *qwd = new ConfigRevoWidget(this);
ftw->removeTab(ConfigGadgetWidget::sensors); stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Attitude"));
icon = new QIcon(); qwd = new ConfigRevoHWWidget(this);
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); stackWidget->replaceTab(ConfigGadgetWidget::hardware, qwd);
icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigRevoHWWidget(this);
ftw->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
} else { } else {
// Unknown board // Unknown board
qDebug() << "Unknown board " << board; qDebug() << "Unknown board " << board;
} }
ftw->setCurrentIndex(selectedIndex);
} }
emit autopilotConnected(); emit autopilotConnected();
@ -244,7 +210,7 @@ void ConfigGadgetWidget::tabAboutToChange(int i, bool *proceed)
{ {
Q_UNUSED(i); Q_UNUSED(i);
*proceed = true; *proceed = true;
ConfigTaskWidget *wid = qobject_cast<ConfigTaskWidget *>(ftw->currentWidget()); ConfigTaskWidget *wid = qobject_cast<ConfigTaskWidget *>(stackWidget->currentWidget());
if (!wid) { if (!wid) {
return; return;
} }
@ -275,7 +241,7 @@ void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *)
icon->addFile(":/configgadget/images/pipx-selected.png", QSize(), QIcon::Selected, QIcon::Off); icon->addFile(":/configgadget/images/pipx-selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigPipXtremeWidget(this); QWidget *qwd = new ConfigPipXtremeWidget(this);
ftw->insertTab(ConfigGadgetWidget::oplink, qwd, *icon, QString("OPLink")); stackWidget->insertTab(ConfigGadgetWidget::oplink, qwd, *icon, QString("OPLink"));
oplinkConnected = true; oplinkConnected = true;
} }
} }
@ -284,6 +250,10 @@ void ConfigGadgetWidget::onOPLinkDisconnect()
{ {
qDebug() << "ConfigGadgetWidget onOPLinkDisconnect"; qDebug() << "ConfigGadgetWidget onOPLinkDisconnect";
oplinkTimeout->stop(); oplinkTimeout->stop();
ftw->removeTab(ConfigGadgetWidget::oplink);
oplinkConnected = false; oplinkConnected = false;
if (stackWidget->currentIndex() == ConfigGadgetWidget::oplink) {
stackWidget->setCurrentIndex(0);
}
stackWidget->removeTab(ConfigGadgetWidget::oplink);
} }

View File

@ -65,7 +65,6 @@ signals:
protected: protected:
void resizeEvent(QResizeEvent *event); void resizeEvent(QResizeEvent *event);
MyTabbedStackWidget *ftw;
private: private:
UAVDataObject *oplinkStatusObj; UAVDataObject *oplinkStatusObj;
@ -73,6 +72,8 @@ private:
// A timer that timesout the connction to the OPLink. // A timer that timesout the connction to the OPLink.
QTimer *oplinkTimeout; QTimer *oplinkTimeout;
bool oplinkConnected; bool oplinkConnected;
MyTabbedStackWidget *stackWidget;
}; };
#endif // CONFIGGADGETWIDGET_H #endif // CONFIGGADGETWIDGET_H

View File

@ -80,41 +80,46 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
unsigned int indexRT = 0; unsigned int indexRT = 0;
foreach(QString name, manualSettingsObj->getField("ChannelNumber")->getElementNames()) { foreach(QString name, manualSettingsObj->getField("ChannelNumber")->getElementNames()) {
Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM); Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM);
InputChannelForm *inpForm = new InputChannelForm(this, index == 0); InputChannelForm *form = new InputChannelForm(index, this);
ui->channelSettings->layout()->addWidget(inpForm); // Add the row to the UI form->setName(name);
inpForm->setName(name); form->moveTo(*(ui->channelLayout));
// The order of the following binding calls is important. Since the values will be populated // The order of the following binding calls is important. Since the values will be populated
// in reverse order of the binding order otherwise the 'Reversed' logic will floor the neutral value // in reverse order of the binding order otherwise the 'Reversed' logic will floor the neutral value
// to the max value ( which is smaller than the neutral value when reversed ) and the channel number // to the max value ( which is smaller than the neutral value when reversed ) and the channel number
// will not be set correctly. // will not be set correctly.
addWidgetBinding("ManualControlSettings", "ChannelNumber", inpForm->ui->channelNumber, index); addWidgetBinding("ManualControlSettings", "ChannelNumber", form->ui->channelNumber, index);
addWidgetBinding("ManualControlSettings", "ChannelGroups", inpForm->ui->channelGroup, index); addWidgetBinding("ManualControlSettings", "ChannelGroups", form->ui->channelGroup, index);
addWidgetBinding("ManualControlSettings", "ChannelNeutral", inpForm->ui->channelNeutral, index); addWidgetBinding("ManualControlSettings", "ChannelNeutral", form->ui->channelNeutral, index);
addWidgetBinding("ManualControlSettings", "ChannelNeutral", inpForm->ui->neutralValue, index); addWidgetBinding("ManualControlSettings", "ChannelNeutral", form->ui->neutralValue, index);
addWidgetBinding("ManualControlSettings", "ChannelMax", inpForm->ui->channelMax, index); addWidgetBinding("ManualControlSettings", "ChannelMax", form->ui->channelMax, index);
addWidgetBinding("ManualControlSettings", "ChannelMin", inpForm->ui->channelMin, index); addWidgetBinding("ManualControlSettings", "ChannelMin", form->ui->channelMin, index);
addWidgetBinding("ManualControlSettings", "ChannelMax", inpForm->ui->channelMax, index); addWidgetBinding("ManualControlSettings", "ChannelMax", form->ui->channelMax, index);
addWidget(inpForm->ui->channelNumberDropdown); addWidget(form->ui->channelRev);
addWidget(inpForm->ui->channelResponseTime);
addWidget(inpForm->ui->channelRev); // Reversing supported for some channels only
bool reversable = ((index == ManualControlSettings::CHANNELGROUPS_THROTTLE) ||
(index == ManualControlSettings::CHANNELGROUPS_ROLL) ||
(index == ManualControlSettings::CHANNELGROUPS_PITCH) ||
(index == ManualControlSettings::CHANNELGROUPS_YAW));
form->ui->channelRev->setVisible(reversable);
// Input filter response time fields supported for some channels only // Input filter response time fields supported for some channels only
switch (index) { switch (index) {
case ManualControlSettings::CHANNELGROUPS_ROLL: case ManualControlSettings::CHANNELGROUPS_ROLL:
case ManualControlSettings::CHANNELGROUPS_PITCH: case ManualControlSettings::CHANNELGROUPS_PITCH:
case ManualControlSettings::CHANNELGROUPS_YAW: case ManualControlSettings::CHANNELGROUPS_YAW:
case ManualControlSettings::CHANNELGROUPS_COLLECTIVE:
case ManualControlSettings::CHANNELGROUPS_ACCESSORY0: case ManualControlSettings::CHANNELGROUPS_ACCESSORY0:
case ManualControlSettings::CHANNELGROUPS_ACCESSORY1: case ManualControlSettings::CHANNELGROUPS_ACCESSORY1:
case ManualControlSettings::CHANNELGROUPS_ACCESSORY2: case ManualControlSettings::CHANNELGROUPS_ACCESSORY2:
addWidgetBinding("ManualControlSettings", "ResponseTime", inpForm->ui->channelResponseTime, indexRT); addWidgetBinding("ManualControlSettings", "ResponseTime", form->ui->channelResponseTime, indexRT);
++indexRT; ++indexRT;
break; break;
case ManualControlSettings::CHANNELGROUPS_THROTTLE: case ManualControlSettings::CHANNELGROUPS_THROTTLE:
case ManualControlSettings::CHANNELGROUPS_FLIGHTMODE: case ManualControlSettings::CHANNELGROUPS_FLIGHTMODE:
case ManualControlSettings::CHANNELGROUPS_COLLECTIVE: form->ui->channelResponseTime->setVisible(false);
inpForm->ui->channelResponseTime->setEnabled(false);
break; break;
default: default:
Q_ASSERT(0); Q_ASSERT(0);

View File

@ -76,10 +76,12 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
// NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10. // NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10.
// Register for ActuatorSettings changes: // Register for ActuatorSettings changes:
for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) { for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) {
OutputChannelForm *form = new OutputChannelForm(i, this, i == 0); OutputChannelForm *form = new OutputChannelForm(i, this);
form->moveTo(*(ui->channelLayout));
connect(ui->channelOutTest, SIGNAL(toggled(bool)), form, SLOT(enableChannelTest(bool))); connect(ui->channelOutTest, SIGNAL(toggled(bool)), form, SLOT(enableChannelTest(bool)));
connect(form, SIGNAL(channelChanged(int, int)), this, SLOT(sendChannelTest(int, int))); connect(form, SIGNAL(channelChanged(int, int)), this, SLOT(sendChannelTest(int, int)));
ui->channelLayout->addWidget(form);
addWidget(form->ui.actuatorMin); addWidget(form->ui.actuatorMin);
addWidget(form->ui.actuatorNeutral); addWidget(form->ui.actuatorNeutral);
addWidget(form->ui.actuatorMax); addWidget(form->ui.actuatorMax);
@ -194,7 +196,7 @@ OutputChannelForm *ConfigOutputWidget::getOutputChannelForm(const int index) con
/** /**
* Set the label for a channel output assignement * Set the label for a channel output assignement
*/ */
void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str) void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString &str)
{ {
// FIXME: use signal/ slot approach // FIXME: use signal/ slot approach
UAVObjectField *field = obj->getField(str); UAVObjectField *field = obj->getField(str);
@ -204,7 +206,7 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str)
OutputChannelForm *outputChannelForm = getOutputChannelForm(index); OutputChannelForm *outputChannelForm = getOutputChannelForm(index);
if (outputChannelForm) { if (outputChannelForm) {
outputChannelForm->setAssignment(str); outputChannelForm->setName(str);
} }
} }
@ -254,15 +256,15 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject *obj)
// Initialize output forms // Initialize output forms
QList<OutputChannelForm *> outputChannelForms = findChildren<OutputChannelForm *>(); QList<OutputChannelForm *> outputChannelForms = findChildren<OutputChannelForm *>();
foreach(OutputChannelForm * outputChannelForm, outputChannelForms) { foreach(OutputChannelForm * outputChannelForm, outputChannelForms) {
outputChannelForm->setAssignment(ChannelDesc[outputChannelForm->index()]); outputChannelForm->setName(ChannelDesc[outputChannelForm->index()]);
// init min,max,neutral // init min,max,neutral
int minValue = actuatorSettingsData.ChannelMin[outputChannelForm->index()]; int minValue = actuatorSettingsData.ChannelMin[outputChannelForm->index()];
int maxValue = actuatorSettingsData.ChannelMax[outputChannelForm->index()]; int maxValue = actuatorSettingsData.ChannelMax[outputChannelForm->index()];
outputChannelForm->minmax(minValue, maxValue); outputChannelForm->setRange(minValue, maxValue);
int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()]; int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()];
outputChannelForm->neutral(neutral); outputChannelForm->setNeutral(neutral);
} }
// Get the SpinWhileArmed setting // Get the SpinWhileArmed setting
@ -349,10 +351,10 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject *obj)
int minValue = actuatorSettingsData.ChannelMin[outputChannelForm->index()]; int minValue = actuatorSettingsData.ChannelMin[outputChannelForm->index()];
int maxValue = actuatorSettingsData.ChannelMax[outputChannelForm->index()]; int maxValue = actuatorSettingsData.ChannelMax[outputChannelForm->index()];
outputChannelForm->minmax(minValue, maxValue); outputChannelForm->setRange(minValue, maxValue);
int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()]; int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()];
outputChannelForm->neutral(neutral); outputChannelForm->setNeutral(neutral);
} }
setDirty(dirty); setDirty(dirty);

View File

@ -47,6 +47,8 @@ public:
ConfigOutputWidget(QWidget *parent = 0); ConfigOutputWidget(QWidget *parent = 0);
~ConfigOutputWidget(); ~ConfigOutputWidget();
protected:
void enableControls(bool enable);
private: private:
Ui_OutputWidget *ui; Ui_OutputWidget *ui;
@ -55,14 +57,14 @@ private:
void updateChannelInSlider(QSlider *slider, QLabel *min, QLabel *max, QCheckBox *rev, int value); void updateChannelInSlider(QSlider *slider, QLabel *min, QLabel *max, QCheckBox *rev, int value);
void assignChannel(UAVDataObject *obj, QString str); void assignOutputChannel(UAVDataObject *obj, QString &str);
void assignOutputChannel(UAVDataObject *obj, QString str);
OutputChannelForm *getOutputChannelForm(const int index) const; OutputChannelForm *getOutputChannelForm(const int index) const;
int mccDataRate; int mccDataRate;
UAVObject::Metadata accInitialData; UAVObject::Metadata accInitialData;
bool wasItMe; bool wasItMe;
private slots: private slots:
void stopTests(); void stopTests();
void disableIfNotMe(UAVObject *obj); void disableIfNotMe(UAVObject *obj);
@ -71,8 +73,6 @@ private slots:
void runChannelTests(bool state); void runChannelTests(bool state);
void sendChannelTest(int index, int value); void sendChannelTest(int index, int value);
void openHelp(); void openHelp();
protected:
void enableControls(bool enable);
}; };
#endif // ifndef CONFIGOUTPUTWIDGET_H #endif // CONFIGOUTPUTWIDGET_H

View File

@ -116,8 +116,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>774</width> <width>772</width>
<height>748</height> <height>751</height>
</rect> </rect>
</property> </property>
<layout class="QGridLayout" name="gridLayout"> <layout class="QGridLayout" name="gridLayout">
@ -143,16 +143,16 @@
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_6"> <layout class="QVBoxLayout" name="verticalLayout_6">
<property name="leftMargin"> <property name="leftMargin">
<number>12</number> <number>9</number>
</property> </property>
<property name="topMargin"> <property name="topMargin">
<number>0</number> <number>9</number>
</property> </property>
<property name="rightMargin"> <property name="rightMargin">
<number>12</number> <number>9</number>
</property> </property>
<property name="bottomMargin"> <property name="bottomMargin">
<number>0</number> <number>9</number>
</property> </property>
<item> <item>
<widget class="QStackedWidget" name="stackedWidget"> <widget class="QStackedWidget" name="stackedWidget">
@ -162,21 +162,21 @@
<widget class="QWidget" name="advancedPage"> <widget class="QWidget" name="advancedPage">
<layout class="QVBoxLayout" name="verticalLayout_3"> <layout class="QVBoxLayout" name="verticalLayout_3">
<property name="leftMargin"> <property name="leftMargin">
<number>12</number> <number>0</number>
</property> </property>
<property name="topMargin"> <property name="topMargin">
<number>12</number> <number>0</number>
</property> </property>
<property name="rightMargin"> <property name="rightMargin">
<number>12</number> <number>0</number>
</property> </property>
<property name="bottomMargin"> <property name="bottomMargin">
<number>12</number> <number>0</number>
</property> </property>
<item> <item>
<layout class="QVBoxLayout" name="channelSettings"> <layout class="QGridLayout" name="channelLayout">
<property name="spacing"> <property name="horizontalSpacing">
<number>0</number> <number>12</number>
</property> </property>
</layout> </layout>
</item> </item>
@ -198,7 +198,7 @@
</item> </item>
<item> <item>
<layout class="QGridLayout" name="gridLayout_3"> <layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="4"> <item row="0" column="3">
<spacer name="horizontalSpacer_3"> <spacer name="horizontalSpacer_3">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
@ -211,14 +211,14 @@
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="0" column="1"> <item row="0" column="0">
<widget class="QLabel" name="labelDeadband"> <widget class="QLabel" name="labelDeadband">
<property name="text"> <property name="text">
<string>Roll/Pitch/Yaw stick deadband</string> <string>Roll/Pitch/Yaw stick deadband</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="0" column="1">
<widget class="QDoubleSpinBox" name="deadband"> <widget class="QDoubleSpinBox" name="deadband">
<property name="toolTip"> <property name="toolTip">
<string>Stick deadband in percents of full range (0-10), zero to disable</string> <string>Stick deadband in percents of full range (0-10), zero to disable</string>
@ -234,22 +234,6 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="0">
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>12</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout> </layout>
</item> </item>
<item> <item>
@ -260,7 +244,7 @@
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>20</width> <width>20</width>
<height>40</height> <height>10</height>
</size> </size>
</property> </property>
</spacer> </spacer>
@ -369,6 +353,12 @@
</item> </item>
<item> <item>
<widget class="QPushButton" name="configurationWizard"> <widget class="QPushButton" name="configurationWizard">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>210</width> <width>210</width>
@ -413,6 +403,12 @@
<property name="enabled"> <property name="enabled">
<bool>true</bool> <bool>true</bool>
</property> </property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>210</width> <width>210</width>
@ -546,8 +542,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>774</width> <width>772</width>
<height>748</height> <height>751</height>
</rect> </rect>
</property> </property>
<layout class="QGridLayout" name="gridLayout_7" rowstretch="1,0,0,0"> <layout class="QGridLayout" name="gridLayout_7" rowstretch="1,0,0,0">
@ -2048,8 +2044,8 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>504</width> <width>772</width>
<height>156</height> <height>751</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_2"> <layout class="QVBoxLayout" name="verticalLayout_2">
@ -2238,7 +2234,7 @@ Set to 0 to disable (recommended for soaring fixed wings).</string>
<string/> <string/>
</property> </property>
<property name="icon"> <property name="icon">
<iconset resource="../coreplugin/core.qrc"> <iconset>
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset> <normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property> </property>
<property name="iconSize"> <property name="iconSize">

View File

@ -4,69 +4,36 @@
#include "manualcontrolsettings.h" #include "manualcontrolsettings.h"
#include "gcsreceiver.h" #include "gcsreceiver.h"
InputChannelForm::InputChannelForm(QWidget *parent, bool showlegend) : InputChannelForm::InputChannelForm(const int index, QWidget *parent) :
ConfigTaskWidget(parent), ChannelForm(index, parent), ui(new Ui::InputChannelForm)
ui(new Ui::InputChannelForm)
{ {
ui->setupUi(this); ui->setupUi(this);
// The first time through the loop, keep the legend. All other times, delete it.
if (!showlegend) {
layout()->removeWidget(ui->legend0);
layout()->removeWidget(ui->legend1);
layout()->removeWidget(ui->legend2);
layout()->removeWidget(ui->legend3);
layout()->removeWidget(ui->legend4);
layout()->removeWidget(ui->legend5);
layout()->removeWidget(ui->legend6);
layout()->removeWidget(ui->legend7);
delete ui->legend0;
delete ui->legend1;
delete ui->legend2;
delete ui->legend3;
delete ui->legend4;
delete ui->legend5;
delete ui->legend6;
delete ui->legend7;
}
connect(ui->channelMin, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated())); connect(ui->channelMin, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated()));
connect(ui->channelMax, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated())); connect(ui->channelMax, SIGNAL(valueChanged(int)), this, SLOT(minMaxUpdated()));
connect(ui->neutralValue, SIGNAL(valueChanged(int)), this, SLOT(neutralUpdated())); connect(ui->neutralValue, SIGNAL(valueChanged(int)), this, SLOT(neutralUpdated()));
connect(ui->channelGroup, SIGNAL(currentIndexChanged(int)), this, SLOT(groupUpdated())); connect(ui->channelGroup, SIGNAL(currentIndexChanged(int)), this, SLOT(groupUpdated()));
connect(ui->channelRev, SIGNAL(toggled(bool)), this, SLOT(reversedUpdated())); connect(ui->channelRev, SIGNAL(toggled(bool)), this, SLOT(reversedUpdated()));
// This is awkward but since we want the UI to be a dropdown but the field is not an enum
// it breaks the UAUVObject widget relation of the task gadget. Running the data through
// a spin box fixes this
connect(ui->channelNumberDropdown, SIGNAL(currentIndexChanged(int)), this, SLOT(channelDropdownUpdated(int)));
connect(ui->channelNumber, SIGNAL(valueChanged(int)), this, SLOT(channelNumberUpdated(int)));
disableMouseWheelEvents(); disableMouseWheelEvents();
} }
InputChannelForm::~InputChannelForm() InputChannelForm::~InputChannelForm()
{ {
delete ui; delete ui;
} }
void InputChannelForm::setName(QString &name) QString InputChannelForm::name()
{
return ui->channelName->text();
}
/**
* Set the channel assignment label.
*/
void InputChannelForm::setName(const QString &name)
{ {
ui->channelName->setText(name); ui->channelName->setText(name);
QFontMetrics metrics(ui->channelName->font());
int width = metrics.width(name) + 5;
foreach(InputChannelForm * form, parent()->findChildren<InputChannelForm *>()) {
if (form == this) {
continue;
}
if (form->ui->channelName->minimumSize().width() < width) {
form->ui->channelName->setMinimumSize(width, 0);
} else {
width = form->ui->channelName->minimumSize().width();
}
}
ui->channelName->setMinimumSize(width, 0);
} }
/** /**
@ -136,8 +103,8 @@ void InputChannelForm::reversedUpdated()
*/ */
void InputChannelForm::groupUpdated() void InputChannelForm::groupUpdated()
{ {
ui->channelNumberDropdown->clear(); ui->channelNumber->clear();
ui->channelNumberDropdown->addItem("Disabled"); ui->channelNumber->addItem("Disabled");
quint8 count = 0; quint8 count = 0;
@ -168,25 +135,6 @@ void InputChannelForm::groupUpdated()
} }
for (int i = 0; i < count; i++) { for (int i = 0; i < count; i++) {
ui->channelNumberDropdown->addItem(QString(tr("Chan %1").arg(i + 1))); ui->channelNumber->addItem(QString(tr("Chan %1").arg(i + 1)));
} }
ui->channelNumber->setMaximum(count);
ui->channelNumber->setMinimum(0);
}
/**
* Update the dropdown from the hidden control
*/
void InputChannelForm::channelDropdownUpdated(int newval)
{
ui->channelNumber->setValue(newval);
}
/**
* Update the hidden control from the dropdown
*/
void InputChannelForm::channelNumberUpdated(int newval)
{
ui->channelNumberDropdown->setCurrentIndex(newval);
} }

View File

@ -1,27 +1,32 @@
#ifndef INPUTCHANNELFORM_H #ifndef INPUTCHANNELFORM_H
#define INPUTCHANNELFORM_H #define INPUTCHANNELFORM_H
#include <QWidget> #include "channelform.h"
#include "configinputwidget.h" #include "configinputwidget.h"
#include <QWidget>
namespace Ui { namespace Ui {
class InputChannelForm; class InputChannelForm;
} }
class InputChannelForm : public ConfigTaskWidget { class InputChannelForm : public ChannelForm {
Q_OBJECT Q_OBJECT
public: public:
explicit InputChannelForm(QWidget *parent = 0, bool showlegend = false); explicit InputChannelForm(const int index, QWidget *parent = NULL);
~InputChannelForm(); ~InputChannelForm();
friend class ConfigInputWidget; friend class ConfigInputWidget;
void setName(QString &name);
virtual QString name();
virtual void setName(const QString &name);
private slots: private slots:
void minMaxUpdated(); void minMaxUpdated();
void neutralUpdated(); void neutralUpdated();
void reversedUpdated(); void reversedUpdated();
void groupUpdated(); void groupUpdated();
void channelDropdownUpdated(int);
void channelNumberUpdated(int);
private: private:
Ui::InputChannelForm *ui; Ui::InputChannelForm *ui;

View File

@ -6,8 +6,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>828</width> <width>923</width>
<height>93</height> <height>51</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
@ -24,268 +24,18 @@
<number>0</number> <number>0</number>
</property> </property>
<property name="bottomMargin"> <property name="bottomMargin">
<number>6</number> <number>0</number>
</property>
<property name="horizontalSpacing">
<number>12</number>
</property> </property>
<item row="0" column="5" colspan="2">
<widget class="QLabel" name="legend4">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel neutral</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Neutral</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="8">
<widget class="QSpinBox" name="channelMax">
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::UpDownArrows</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>1000</number>
</property>
</widget>
</item>
<item row="0" column="12">
<widget class="QLabel" name="legend7">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>30</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Response time</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="text">
<string>RT</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="10" colspan="2">
<widget class="QLabel" name="legend6">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>75</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel values are inverted</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="text">
<string>Reversed</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="legend0">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel function</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Function</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="legend1">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel type</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Type</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2"> <item row="0" column="2">
<widget class="QLabel" name="legend2"> <widget class="QLabel" name="legend2">
<property name="enabled"> <property name="enabled">
<bool>true</bool> <bool>true</bool>
</property> </property>
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -298,6 +48,7 @@ font:bold;</string>
</property> </property>
<property name="font"> <property name="font">
<font> <font>
<pointsize>-1</pointsize>
<weight>75</weight> <weight>75</weight>
<italic>false</italic> <italic>false</italic>
<bold>true</bold> <bold>true</bold>
@ -310,8 +61,8 @@ font:bold;</string>
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); <string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255); color: rgb(255, 255, 255);
border-radius: 5; border-radius: 5;
margin:1px; font: bold 12px;
font:bold;</string> margin:1px;</string>
</property> </property>
<property name="frameShape"> <property name="frameShape">
<enum>QFrame::StyledPanel</enum> <enum>QFrame::StyledPanel</enum>
@ -324,133 +75,47 @@ font:bold;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="3"> <item row="0" column="4">
<widget class="QLabel" name="legend3"> <spacer name="horizontalSpacer_3">
<property name="enabled"> <property name="orientation">
<bool>true</bool> <enum>Qt::Horizontal</enum>
</property> </property>
<property name="sizePolicy"> <property name="sizeType">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <enum>QSizePolicy::Fixed</enum>
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property> </property>
<property name="minimumSize"> <property name="sizeHint" stdset="0">
<size> <size>
<width>0</width> <width>10</width>
<height>20</height> <height>20</height>
</size> </size>
</property> </property>
<property name="font"> </spacer>
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel min</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item> </item>
<item row="1" column="0"> <item row="1" column="3">
<widget class="QLabel" name="channelName"> <widget class="QSpinBox" name="channelMin">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="minimumSize">
<size>
<width>80</width>
<height>25</height>
</size>
</property>
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="channelNumberDropdown">
<property name="sizePolicy">
<sizepolicy hsizetype="Maximum" vsizetype="Fixed">
<horstretch>4</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>25</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize"> <property name="maximumSize">
<size> <size>
<width>90</width> <width>16777215</width>
<height>16777215</height> <height>16777215</height>
</size> </size>
</property> </property>
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
</property> </property>
<property name="maxVisibleItems"> <property name="alignment">
<number>7</number> <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="channelGroup">
<property name="sizePolicy">
<sizepolicy hsizetype="Maximum" vsizetype="Fixed">
<horstretch>6</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QSpinBox" name="channelMin">
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property> </property>
<property name="buttonSymbols"> <property name="buttonSymbols">
<enum>QAbstractSpinBox::UpDownArrows</enum> <enum>QAbstractSpinBox::UpDownArrows</enum>
@ -463,123 +128,111 @@ font:bold;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="4"> <item row="1" column="1">
<spacer name="horizontalSpacer"> <widget class="QComboBox" name="channelGroup">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="8">
<widget class="QLabel" name="legend5">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>110</width>
<height>20</height> <height>0</height>
</size> </size>
</property> </property>
<property name="font"> <property name="maximumSize">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel max</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="7">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size> <size>
<width>10</width> <width>16777215</width>
<height>20</height> <height>16777215</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="5">
<widget class="QSlider" name="channelNeutral">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>22</height>
</size> </size>
</property> </property>
<property name="focusPolicy"> <property name="focusPolicy">
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
</property> </property>
<property name="orientation"> <property name="sizeAdjustPolicy">
<enum>Qt::Horizontal</enum> <enum>QComboBox::AdjustToContents</enum>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="12"> <item row="1" column="2">
<widget class="QSpinBox" name="channelResponseTime"> <widget class="QComboBox" name="channelNumber">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>30</width> <width>100</width>
<height>25</height> <height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="maxVisibleItems">
<number>7</number>
</property>
<property name="sizeAdjustPolicy">
<enum>QComboBox::AdjustToContents</enum>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="channelName">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>Text</string>
</property>
</widget>
</item>
<item row="1" column="9">
<widget class="QSpinBox" name="channelResponseTime">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size> </size>
</property> </property>
<property name="toolTip"> <property name="toolTip">
@ -598,6 +251,9 @@ even lead to crash. Use with caution.</string>
<property name="frame"> <property name="frame">
<bool>true</bool> <bool>true</bool>
</property> </property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="buttonSymbols"> <property name="buttonSymbols">
<enum>QAbstractSpinBox::UpDownArrows</enum> <enum>QAbstractSpinBox::UpDownArrows</enum>
</property> </property>
@ -606,21 +262,544 @@ even lead to crash. Use with caution.</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="10" colspan="2"> <item row="0" column="0">
<widget class="QLabel" name="legend0">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel function</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Function</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="7">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="4">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="7">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="8">
<widget class="QLabel" name="legend6">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel values are inverted</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="text">
<string>Reversed</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="9">
<widget class="QLabel" name="legend7">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Response time</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="text">
<string>RT</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="6">
<widget class="QLabel" name="legend5">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel max</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="5">
<widget class="QLabel" name="legend4">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel neutral</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Neutral</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="legend3">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel min</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="legend1">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>Channel type</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="text">
<string>Type</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="6">
<widget class="QSpinBox" name="channelMax">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::UpDownArrows</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>1000</number>
</property>
</widget>
</item>
<item row="1" column="5">
<widget class="QFrame" name="frame"> <widget class="QFrame" name="frame">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="leftMargin">
<number>2</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>2</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QSlider" name="channelNeutral">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="neutralValue">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>1000</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="1" column="8">
<widget class="QFrame" name="frame_1">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>75</width> <width>75</width>
<height>0</height> <height>0</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="frameShape"> <property name="frameShape">
<enum>QFrame::NoFrame</enum> <enum>QFrame::NoFrame</enum>
</property> </property>
<property name="frameShadow"> <property name="frameShadow">
<enum>QFrame::Raised</enum> <enum>QFrame::Raised</enum>
</property> </property>
<layout class="QGridLayout" name="gridLayout_2"> <layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="leftMargin"> <property name="leftMargin">
<number>0</number> <number>0</number>
</property> </property>
@ -633,15 +812,21 @@ even lead to crash. Use with caution.</string>
<property name="bottomMargin"> <property name="bottomMargin">
<number>0</number> <number>0</number>
</property> </property>
<item row="0" column="0" alignment="Qt::AlignHCenter"> <item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="channelRev"> <widget class="QCheckBox" name="channelRev">
<property name="enabled"> <property name="enabled">
<bool>true</bool> <bool>true</bool>
</property> </property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>20</height> <height>0</height>
</size> </size>
</property> </property>
<property name="text"> <property name="text">
@ -652,51 +837,8 @@ even lead to crash. Use with caution.</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="1" column="6">
<widget class="QSpinBox" name="neutralValue">
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>1000</number>
</property>
</widget>
</item>
</layout> </layout>
<widget class="QSpinBox" name="channelNumber">
<property name="enabled">
<bool>true</bool>
</property>
<property name="geometry">
<rect>
<x>216</x>
<y>26</y>
<width>0</width>
<height>0</height>
</rect>
</property>
<property name="maximumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
</widget>
</widget> </widget>
<tabstops>
<tabstop>channelNumber</tabstop>
<tabstop>channelGroup</tabstop>
<tabstop>channelNumberDropdown</tabstop>
<tabstop>channelMin</tabstop>
<tabstop>channelNeutral</tabstop>
<tabstop>channelMax</tabstop>
</tabstops>
<resources/> <resources/>
<connections/> <connections/>
</ui> </ui>

View File

@ -122,8 +122,8 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>676</width> <width>674</width>
<height>674</height> <height>677</height>
</rect> </rect>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout_3"> <layout class="QVBoxLayout" name="verticalLayout_3">
@ -654,41 +654,46 @@ Leave at 50Hz for fixed wing.</string>
</property> </property>
<layout class="QVBoxLayout" name="verticalLayout"> <layout class="QVBoxLayout" name="verticalLayout">
<item> <item>
<layout class="QVBoxLayout" name="channelLayout"> <layout class="QGridLayout" name="channelLayout">
<property name="sizeConstraint"> <property name="horizontalSpacing">
<enum>QLayout::SetDefaultConstraint</enum> <number>12</number>
</property> </property>
</layout> </layout>
</item> </item>
<item> <item>
<layout class="QHBoxLayout" name="horizontalLayout_2"> <spacer name="verticalSpacer_2">
<item> <property name="orientation">
<widget class="QCheckBox" name="spinningArmed"> <enum>Qt::Vertical</enum>
<property name="minimumSize"> </property>
<size> <property name="sizeType">
<width>519</width> <enum>QSizePolicy::Fixed</enum>
<height>20</height> </property>
</size> <property name="sizeHint" stdset="0">
</property> <size>
<property name="text"> <width>20</width>
<string>Motors spin at neutral output when armed and throttle below zero (be careful)</string> <height>10</height>
</property> </size>
</widget> </property>
</item> </spacer>
<item> </item>
<spacer name="horizontalSpacer_2"> <item>
<property name="orientation"> <widget class="QCheckBox" name="spinningArmed">
<enum>Qt::Horizontal</enum> <property name="sizePolicy">
</property> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<property name="sizeHint" stdset="0"> <horstretch>0</horstretch>
<size> <verstretch>0</verstretch>
<width>40</width> </sizepolicy>
<height>20</height> </property>
</size> <property name="minimumSize">
</property> <size>
</spacer> <width>519</width>
</item> <height>20</height>
</layout> </size>
</property>
<property name="text">
<string>Motors spin at neutral output when armed and throttle below zero (be careful)</string>
</property>
</widget>
</item> </item>
<item> <item>
<spacer name="verticalSpacer"> <spacer name="verticalSpacer">

View File

@ -26,52 +26,24 @@
*/ */
#include "outputchannelform.h" #include "outputchannelform.h"
#include "configoutputwidget.h"
OutputChannelForm::OutputChannelForm(const int index, QWidget *parent, const bool showLegend) : OutputChannelForm::OutputChannelForm(const int index, QWidget *parent) :
ConfigTaskWidget(parent), ChannelForm(index, parent), ui(), m_inChannelTest(false)
ui(),
m_index(index),
m_inChannelTest(false)
{ {
ui.setupUi(this); ui.setupUi(this);
if (!showLegend) {
// Remove legend
QGridLayout *grid_layout = dynamic_cast<QGridLayout *>(layout());
Q_ASSERT(grid_layout);
for (int col = 0; col < grid_layout->columnCount(); col++) { // remove every item in first row
QLayoutItem *item = grid_layout->itemAtPosition(0, col);
if (!item) {
continue;
}
// get widget from layout item
QWidget *legend_widget = item->widget();
if (!legend_widget) {
continue;
}
// delete widget
grid_layout->removeWidget(legend_widget);
delete legend_widget;
}
}
// The convention for OP is Channel 1 to Channel 10. // The convention for OP is Channel 1 to Channel 10.
ui.actuatorNumber->setText(QString("%1:").arg(m_index + 1)); ui.actuatorNumber->setText(QString("%1:").arg(index + 1));
// Register for ActuatorSettings changes: // Register for ActuatorSettings changes:
connect(ui.actuatorMin, SIGNAL(editingFinished()), connect(ui.actuatorMin, SIGNAL(editingFinished()), this, SLOT(setChannelRange()));
this, SLOT(setChannelRange())); connect(ui.actuatorMax, SIGNAL(editingFinished()), this, SLOT(setChannelRange()));
connect(ui.actuatorMax, SIGNAL(editingFinished()), connect(ui.actuatorRev, SIGNAL(toggled(bool)), this, SLOT(reverseChannel(bool)));
this, SLOT(setChannelRange()));
connect(ui.actuatorRev, SIGNAL(toggled(bool)),
this, SLOT(reverseChannel(bool)));
// Now connect the channel out sliders to our signal to send updates in test mode // Now connect the channel out sliders to our signal to send updates in test mode
connect(ui.actuatorNeutral, SIGNAL(valueChanged(int)), connect(ui.actuatorNeutral, SIGNAL(valueChanged(int)), this, SLOT(sendChannelTest(int)));
this, SLOT(sendChannelTest(int)));
ui.actuatorLink->setChecked(false); ui.actuatorLink->setChecked(false);
connect(ui.actuatorLink, SIGNAL(toggled(bool)), connect(ui.actuatorLink, SIGNAL(toggled(bool)), this, SLOT(linkToggled(bool)));
this, SLOT(linkToggled(bool)));
disableMouseWheelEvents(); disableMouseWheelEvents();
} }
@ -81,6 +53,19 @@ OutputChannelForm::~OutputChannelForm()
// Do nothing // Do nothing
} }
QString OutputChannelForm::name()
{
return ui.actuatorName->text();
}
/**
* Set the channel assignment label.
*/
void OutputChannelForm::setName(const QString &name)
{
ui.actuatorName->setText(name);
}
/** /**
* Restrict UI to protect users from accidental misuse. * Restrict UI to protect users from accidental misuse.
*/ */
@ -149,26 +134,49 @@ void OutputChannelForm::linkToggled(bool state)
} }
} }
int OutputChannelForm::max() const
{
return ui.actuatorMax->value();
}
/** /**
* Set maximal channel value. * Set maximal channel value.
*/ */
void OutputChannelForm::max(int maximum) void OutputChannelForm::setMax(int maximum)
{ {
minmax(ui.actuatorMin->value(), maximum); setRange(ui.actuatorMin->value(), maximum);
}
int OutputChannelForm::min() const
{
return ui.actuatorMin->value();
} }
/** /**
* Set minimal channel value. * Set minimal channel value.
*/ */
void OutputChannelForm::min(int minimum) void OutputChannelForm::setMin(int minimum)
{ {
minmax(minimum, ui.actuatorMax->value()); setRange(minimum, ui.actuatorMax->value());
}
int OutputChannelForm::neutral() const
{
return ui.actuatorNeutral->value();
}
/**
* Set neutral of channel.
*/
void OutputChannelForm::setNeutral(int value)
{
ui.actuatorNeutral->setValue(value);
} }
/** /**
* Set minimal and maximal channel value. * Set minimal and maximal channel value.
*/ */
void OutputChannelForm::minmax(int minimum, int maximum) void OutputChannelForm::setRange(int minimum, int maximum)
{ {
ui.actuatorMin->setValue(minimum); ui.actuatorMin->setValue(minimum);
ui.actuatorMax->setValue(maximum); ui.actuatorMax->setValue(maximum);
@ -180,35 +188,6 @@ void OutputChannelForm::minmax(int minimum, int maximum)
} }
} }
/**
* Set neutral of channel.
*/
void OutputChannelForm::neutral(int value)
{
ui.actuatorNeutral->setValue(value);
}
/**
* Set the channel assignment label.
*/
void OutputChannelForm::setAssignment(const QString &assignment)
{
ui.actuatorName->setText(assignment);
QFontMetrics metrics(ui.actuatorName->font());
int width = metrics.width(assignment) + 1;
foreach(OutputChannelForm * form, parent()->findChildren<OutputChannelForm *>()) {
if (form == this) {
continue;
}
if (form->ui.actuatorName->minimumSize().width() < width) {
form->ui.actuatorName->setMinimumSize(width, 0);
} else {
width = form->ui.actuatorName->minimumSize().width();
}
}
ui.actuatorName->setMinimumSize(width, 0);
}
/** /**
* Sets the minimum/maximum value of the channel output sliders. * Sets the minimum/maximum value of the channel output sliders.
* Have to do it here because setMinimum is not a slot. * Have to do it here because setMinimum is not a slot.
@ -220,7 +199,7 @@ void OutputChannelForm::setChannelRange()
{ {
int oldMini = ui.actuatorNeutral->minimum(); int oldMini = ui.actuatorNeutral->minimum();
// int oldMaxi = ui.actuatorNeutral->maximum(); // int oldMaxi = ui.actuatorNeutral->maximum();
if (ui.actuatorMin->value() < ui.actuatorMax->value()) { if (ui.actuatorMin->value() < ui.actuatorMax->value()) {
ui.actuatorNeutral->setRange(ui.actuatorMin->value(), ui.actuatorMax->value()); ui.actuatorNeutral->setRange(ui.actuatorMin->value(), ui.actuatorMax->value());
@ -234,8 +213,9 @@ void OutputChannelForm::setChannelRange()
ui.actuatorNeutral->setValue(ui.actuatorNeutral->minimum()); ui.actuatorNeutral->setValue(ui.actuatorNeutral->minimum());
} }
// if (ui.actuatorNeutral->value() == oldMaxi) // if (ui.actuatorNeutral->value() == oldMaxi)
// ui.actuatorNeutral->setValue(ui.actuatorNeutral->maximum()); // this can be dangerous if it happens to be controlling a motor at the time! // this can be dangerous if it happens to be controlling a motor at the time!
// ui.actuatorNeutral->setValue(ui.actuatorNeutral->maximum());
} }
/** /**
@ -252,8 +232,7 @@ void OutputChannelForm::reverseChannel(bool state)
return; return;
} }
// Now, swap the min & max values (only on the spinboxes, the slider // Now, swap the min & max values (only on the spinboxes, the slider does not change!)
// does not change!
int temp = ui.actuatorMax->value(); int temp = ui.actuatorMax->value();
ui.actuatorMax->setValue(ui.actuatorMin->value()); ui.actuatorMax->setValue(ui.actuatorMin->value());
ui.actuatorMin->setValue(temp); ui.actuatorMin->setValue(temp);
@ -286,12 +265,14 @@ void OutputChannelForm::sendChannelTest(int value)
} }
if (ui.actuatorRev->isChecked()) { if (ui.actuatorRev->isChecked()) {
value = ui.actuatorMin->value() - value + ui.actuatorMax->value(); // the channel is reversed // the channel is reversed
value = ui.actuatorMin->value() - value + ui.actuatorMax->value();
} }
// update the label // update the label
ui.actuatorValue->setText(QString::number(value)); ui.actuatorValue->setValue(value);
if (ui.actuatorLink->checkState() && parent()) { // the channel is linked to other channels if (ui.actuatorLink->checkState() && parent()) {
// the channel is linked to other channels
QList<OutputChannelForm *> outputChannelForms = parent()->findChildren<OutputChannelForm *>(); QList<OutputChannelForm *> outputChannelForms = parent()->findChildren<OutputChannelForm *>();
// set the linked channels of the parent widget to the same value // set the linked channels of the parent widget to the same value
foreach(OutputChannelForm * outputChannelForm, outputChannelForms) { foreach(OutputChannelForm * outputChannelForm, outputChannelForms) {
@ -315,12 +296,13 @@ void OutputChannelForm::sendChannelTest(int value)
} }
outputChannelForm->ui.actuatorNeutral->setValue(val); outputChannelForm->ui.actuatorNeutral->setValue(val);
outputChannelForm->ui.actuatorValue->setText(QString::number(val)); outputChannelForm->ui.actuatorValue->setValue(val);
} }
} }
if (!m_inChannelTest) { if (!m_inChannelTest) {
return; // we are not in Test Output mode // we are not in Test Output mode
return;
} }
emit channelChanged(index(), value); emit channelChanged(index(), value);
} }

View File

@ -27,29 +27,32 @@
#ifndef OUTPUTCHANNELFORM_H #ifndef OUTPUTCHANNELFORM_H
#define OUTPUTCHANNELFORM_H #define OUTPUTCHANNELFORM_H
#include <QWidget> #include "channelform.h"
#include "configoutputwidget.h"
#include "ui_outputchannelform.h" #include "ui_outputchannelform.h"
#include "configtaskwidget.h"
class OutputChannelForm : public ConfigTaskWidget { #include <QWidget>
class OutputChannelForm : public ChannelForm {
Q_OBJECT Q_OBJECT
public: public:
explicit OutputChannelForm(const int index, QWidget *parent = NULL, const bool showLegend = false); explicit OutputChannelForm(const int index, QWidget *parent = NULL);
~OutputChannelForm(); ~OutputChannelForm();
friend class ConfigOutputWidget; friend class ConfigOutputWidget;
void setAssignment(const QString &assignment); virtual QString name();
int index() const; virtual void setName(const QString &name);
public slots: public slots:
void max(int maximum);
int max() const;
void min(int minimum);
int min() const; int min() const;
void minmax(int minimum, int maximum); void setMin(int minimum);
void neutral(int value); int max() const;
void setMax(int maximum);
int neutral() const; int neutral() const;
void setNeutral(int value);
void setRange(int minimum, int maximum);
void enableChannelTest(bool state); void enableChannelTest(bool state);
signals: signals:
@ -57,8 +60,6 @@ signals:
private: private:
Ui::outputChannelForm ui; Ui::outputChannelForm ui;
/// Channel index
int m_index;
bool m_inChannelTest; bool m_inChannelTest;
private slots: private slots:
@ -68,23 +69,4 @@ private slots:
void setChannelRange(); void setChannelRange();
}; };
inline int OutputChannelForm::index() const
{
return m_index;
}
inline int OutputChannelForm::max() const
{
return ui.actuatorMax->value();
}
inline int OutputChannelForm::min() const
{
return ui.actuatorMin->value();
}
inline int OutputChannelForm::neutral() const
{
return ui.actuatorNeutral->value();
}
#endif // OUTPUTCHANNELFORM_H #endif // OUTPUTCHANNELFORM_H

View File

@ -6,39 +6,52 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>825</width> <width>768</width>
<height>58</height> <height>51</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
<string>Form</string> <string>Form</string>
</property> </property>
<layout class="QGridLayout" name="gridLayout"> <layout class="QGridLayout" name="gridLayout">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin"> <property name="topMargin">
<number>1</number> <number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property> </property>
<property name="bottomMargin"> <property name="bottomMargin">
<number>1</number> <number>0</number>
</property> </property>
<property name="horizontalSpacing"> <property name="horizontalSpacing">
<number>12</number> <number>12</number>
</property> </property>
<item row="0" column="11"> <item row="0" column="1">
<widget class="QLabel" name="legend5"> <widget class="QLabel" name="legend0">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>45</width> <width>0</width>
<height>20</height> <height>20</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="font"> <property name="font">
<font> <font>
<pointsize>-1</pointsize>
<weight>75</weight> <weight>75</weight>
<italic>false</italic> <italic>false</italic>
<bold>true</bold> <bold>true</bold>
@ -48,37 +61,61 @@
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); <string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255); color: rgb(255, 255, 255);
border-radius: 5; border-radius: 5;
font:bold; font: bold 12px;
margin:1px;</string> margin:1px;</string>
</property> </property>
<property name="text"> <property name="text">
<string>Link</string> <string>Assignment</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignCenter</set> <set>Qt::AlignCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="8"> <item row="0" column="2">
<widget class="QSpinBox" name="actuatorMax"> <widget class="QLabel" name="legend1">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>25</height> <height>20</height>
</size> </size>
</property> </property>
<property name="focusPolicy"> <property name="maximumSize">
<enum>Qt::StrongFocus</enum> <size>
<width>16777215</width>
<height>16777215</height>
</size>
</property> </property>
<property name="toolTip"> <property name="font">
<string>Maximum PWM value, beware of not overdriving your servo.</string> <font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property> </property>
<property name="maximum"> <property name="styleSheet">
<number>9999</number> <string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="4" colspan="2"> <item row="0" column="4">
<widget class="QLabel" name="legend2"> <widget class="QLabel" name="legend2">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed"> <sizepolicy hsizetype="Expanding" vsizetype="Fixed">
@ -94,6 +131,7 @@ margin:1px;</string>
</property> </property>
<property name="font"> <property name="font">
<font> <font>
<pointsize>-1</pointsize>
<weight>75</weight> <weight>75</weight>
<italic>false</italic> <italic>false</italic>
<bold>true</bold> <bold>true</bold>
@ -103,7 +141,7 @@ margin:1px;</string>
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); <string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255); color: rgb(255, 255, 255);
border-radius: 5; border-radius: 5;
font:bold; font: bold 12px;
margin:1px;</string> margin:1px;</string>
</property> </property>
<property name="text"> <property name="text">
@ -114,10 +152,26 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="5">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="0"> <item row="0" column="0">
<widget class="QLabel" name="legend6"> <widget class="QLabel" name="legend6">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -128,8 +182,15 @@ margin:1px;</string>
<height>20</height> <height>20</height>
</size> </size>
</property> </property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="font"> <property name="font">
<font> <font>
<pointsize>-1</pointsize>
<weight>75</weight> <weight>75</weight>
<italic>false</italic> <italic>false</italic>
<bold>true</bold> <bold>true</bold>
@ -142,7 +203,7 @@ margin:1px;</string>
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); <string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255); color: rgb(255, 255, 255);
border-radius: 5; border-radius: 5;
font:bold; font: bold 12px;
margin:1px;</string> margin:1px;</string>
</property> </property>
<property name="text"> <property name="text">
@ -156,13 +217,13 @@ margin:1px;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="6"> <item row="0" column="3">
<spacer name="horizontalSpacer_2"> <spacer name="horizontalSpacer_3">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
</property> </property>
<property name="sizeType"> <property name="sizeType">
<enum>QSizePolicy::Minimum</enum> <enum>QSizePolicy::Fixed</enum>
</property> </property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
@ -172,10 +233,42 @@ margin:1px;</string>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="0" column="1"> <item row="1" column="5">
<widget class="QLabel" name="legend0"> <spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="3">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="2">
<widget class="QSpinBox" name="actuatorMin">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -183,37 +276,13 @@ margin:1px;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>20</height> <height>0</height>
</size> </size>
</property> </property>
<property name="font"> <property name="maximumSize">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Assignment</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QSpinBox" name="actuatorMin">
<property name="minimumSize">
<size> <size>
<width>0</width> <width>16777215</width>
<height>25</height> <height>16777215</height>
</size> </size>
</property> </property>
<property name="focusPolicy"> <property name="focusPolicy">
@ -222,69 +291,14 @@ margin:1px;</string>
<property name="toolTip"> <property name="toolTip">
<string>Minimum PWM value, beware of not overdriving your servo.</string> <string>Minimum PWM value, beware of not overdriving your servo.</string>
</property> </property>
<property name="maximum">
<number>9999</number>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QSlider" name="actuatorNeutral">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="0" column="8">
<widget class="QLabel" name="legend3">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignCenter</set> <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>0</number>
</property> </property>
</widget> </widget>
</item> </item>
@ -299,35 +313,154 @@ margin:1px;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>20</width> <width>20</width>
<height>25</height> <height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size> </size>
</property> </property>
<property name="toolTip"> <property name="toolTip">
<string>Channel Number</string> <string>Channel Number</string>
</property> </property>
<property name="text"> <property name="text">
<string>TextLabel</string> <string>0:</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignCenter</set> <set>Qt::AlignCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="3"> <item row="0" column="6">
<spacer name="horizontalSpacer"> <widget class="QLabel" name="legend3">
<property name="orientation"> <property name="sizePolicy">
<enum>Qt::Horizontal</enum> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property> </property>
<property name="sizeType"> <property name="minimumSize">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size> <size>
<width>5</width> <width>0</width>
<height>20</height> <height>20</height>
</size> </size>
</property> </property>
</spacer> <property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="7">
<widget class="QLabel" name="legend4">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Reversed</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="8">
<widget class="QLabel" name="legend5">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Link</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item> </item>
<item row="1" column="1"> <item row="1" column="1">
<widget class="QLabel" name="actuatorName"> <widget class="QLabel" name="actuatorName">
@ -340,21 +473,27 @@ margin:1px;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>110</width> <width>110</width>
<height>25</height> <height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size> </size>
</property> </property>
<property name="text"> <property name="text">
<string>TextLabel</string> <string>-</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignCenter</set> <set>Qt::AlignCenter</set>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="9"> <item row="1" column="6">
<widget class="QLabel" name="legend4"> <widget class="QSpinBox" name="actuatorMax">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -362,98 +501,133 @@ margin:1px;</string>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>0</width> <width>0</width>
<height>20</height> <height>0</height>
</size> </size>
</property> </property>
<property name="font"> <property name="maximumSize">
<font> <size>
<weight>75</weight> <width>16777215</width>
<italic>false</italic> <height>16777215</height>
<bold>true</bold> </size>
</font>
</property> </property>
<property name="styleSheet"> <property name="focusPolicy">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); <enum>Qt::StrongFocus</enum>
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property> </property>
<property name="text"> <property name="toolTip">
<string>Reversed</string> <string>Maximum PWM value, beware of not overdriving your servo.</string>
</property> </property>
<property name="alignment"> <property name="alignment">
<set>Qt::AlignCenter</set> <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="maximum">
<number>9999</number>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="5"> <item row="1" column="4">
<widget class="QLabel" name="actuatorValue"> <widget class="QFrame" name="frame">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<property name="leftMargin">
<number>2</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>2</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QSlider" name="actuatorNeutral">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="actuatorValue">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="frame">
<bool>true</bool>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::UpDownArrows</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="1" column="7">
<widget class="QFrame" name="frame_1">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred"> <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="toolTip">
<string>Current value of slider.</string>
</property>
<property name="text">
<string>0000</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="legend1">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="9">
<widget class="QFrame" name="frame">
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>75</width> <width>75</width>
<height>0</height> <height>0</height>
</size> </size>
</property> </property>
<layout class="QGridLayout" name="gridLayout_2"> <property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>0</number>
</property>
<property name="leftMargin"> <property name="leftMargin">
<number>0</number> <number>0</number>
</property> </property>
@ -466,13 +640,10 @@ margin:1px;</string>
<property name="bottomMargin"> <property name="bottomMargin">
<number>0</number> <number>0</number>
</property> </property>
<property name="spacing"> <item alignment="Qt::AlignHCenter">
<number>0</number>
</property>
<item row="0" column="0">
<widget class="QCheckBox" name="actuatorRev"> <widget class="QCheckBox" name="actuatorRev">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -494,8 +665,14 @@ margin:1px;</string>
</layout> </layout>
</widget> </widget>
</item> </item>
<item row="1" column="11"> <item row="1" column="8">
<widget class="QFrame" name="frame_1"> <widget class="QFrame" name="frame_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize"> <property name="minimumSize">
<size> <size>
<width>45</width> <width>45</width>
@ -506,9 +683,12 @@ margin:1px;</string>
<enum>QFrame::NoFrame</enum> <enum>QFrame::NoFrame</enum>
</property> </property>
<property name="frameShadow"> <property name="frameShadow">
<enum>QFrame::Raised</enum> <enum>QFrame::Plain</enum>
</property> </property>
<layout class="QGridLayout" name="gridLayout_3"> <layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
<number>0</number>
</property>
<property name="leftMargin"> <property name="leftMargin">
<number>0</number> <number>0</number>
</property> </property>
@ -521,13 +701,10 @@ margin:1px;</string>
<property name="bottomMargin"> <property name="bottomMargin">
<number>0</number> <number>0</number>
</property> </property>
<property name="spacing"> <item alignment="Qt::AlignHCenter">
<number>0</number>
</property>
<item row="0" column="0" alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="actuatorLink"> <widget class="QCheckBox" name="actuatorLink">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
@ -551,11 +728,6 @@ margin:1px;</string>
</item> </item>
</layout> </layout>
</widget> </widget>
<tabstops>
<tabstop>actuatorMin</tabstop>
<tabstop>actuatorNeutral</tabstop>
<tabstop>actuatorMax</tabstop>
</tabstops>
<resources/> <resources/>
<connections/> <connections/>
</ui> </ui>

View File

@ -270,7 +270,7 @@ void MainWindow::extensionsInitialized()
// We'll use qApp macro to get the QApplication pointer // We'll use qApp macro to get the QApplication pointer
// and set the style sheet application wide. // and set the style sheet application wide.
qDebug() << "Setting application style sheet to:" << style; // qDebug() << "Setting application style sheet to:" << style;
qApp->setStyleSheet(style); qApp->setStyleSheet(style);
qs->endGroup(); qs->endGroup();

View File

@ -52,8 +52,9 @@ plugin_uavtalk.depends += plugin_coreplugin
# Telemetry plugin # Telemetry plugin
SUBDIRS += plugin_telemetry SUBDIRS += plugin_telemetry
plugin_telemetry.subdir = telemetry plugin_telemetry.subdir = telemetry
plugin_telemetry.depends = plugin_coreplugin
plugin_telemetry.depends += plugin_uavobjectutil
plugin_telemetry.depends += plugin_uavtalk plugin_telemetry.depends += plugin_uavtalk
plugin_telemetry.depends += plugin_coreplugin
# OPMap UAVGadget # OPMap UAVGadget
plugin_opmap.subdir = opmap plugin_opmap.subdir = opmap
@ -98,9 +99,9 @@ macx:contains(QT_VERSION, ^4\\.8\\.0): CONFIG += disable_notify_plugin
plugin_uploader.subdir = uploader plugin_uploader.subdir = uploader
plugin_uploader.depends = plugin_coreplugin plugin_uploader.depends = plugin_coreplugin
plugin_uploader.depends += plugin_uavobjects plugin_uploader.depends += plugin_uavobjects
plugin_uploader.depends += plugin_uavobjectutil
plugin_uploader.depends += plugin_uavtalk plugin_uploader.depends += plugin_uavtalk
plugin_uploader.depends += plugin_opHID plugin_uploader.depends += plugin_opHID
plugin_uploader.depends += plugin_uavobjectutil
SUBDIRS += plugin_uploader SUBDIRS += plugin_uploader
# Dial gadget # Dial gadget

View File

@ -1,12 +1,11 @@
TEMPLATE = lib TEMPLATE = lib
TARGET = Telemetry TARGET = Telemetry
DEFINES += TELEMETRY_LIBRARY
QT += svg QT += svg
include(../../openpilotgcsplugin.pri)
include(../../plugins/coreplugin/coreplugin.pri)
include(../../libs/version_info/version_info.pri)
include(telemetry_dependencies.pri) include(telemetry_dependencies.pri)
include(../../libs/version_info/version_info.pri)
HEADERS += telemetry_global.h \ HEADERS += telemetry_global.h \
telemetryplugin.h \ telemetryplugin.h \
@ -23,8 +22,6 @@ SOURCES += telemetryplugin.cpp \
monitorgadgetfactory.cpp \ monitorgadgetfactory.cpp \
monitorgadgetoptionspage.cpp monitorgadgetoptionspage.cpp
DEFINES += TELEMETRY_LIBRARY OTHER_FILES += Telemetry.pluginspec
RESOURCES += telemetry.qrc RESOURCES += telemetry.qrc
OTHER_FILES += Telemetry.pluginspec

View File

@ -1,4 +1,4 @@
include(../../plugins/uavobjects/uavobjects.pri) include(../../openpilotgcsplugin.pri)
include(../../plugins/coreplugin/coreplugin.pri)
include(../../plugins/uavobjectutil/uavobjectutil.pri) include(../../plugins/uavobjectutil/uavobjectutil.pri)
include(../../plugins/uavtalk/uavtalk.pri) include(../../plugins/uavtalk/uavtalk.pri)

View File

@ -199,14 +199,14 @@ void UAVObjectField::limitsInitialize(const QString &limits)
elementLimits.insert(index, limitList); elementLimits.insert(index, limitList);
++index; ++index;
} }
foreach(QList<LimitStruct> limitList, elementLimits) { // foreach(QList<LimitStruct> limitList, elementLimits) {
foreach(LimitStruct limit, limitList) { // foreach(LimitStruct limit, limitList) {
qDebug() << "Limit type" << limit.type << "for board" << limit.board << "for field" << getName(); // qDebug() << "Limit type" << limit.type << "for board" << limit.board << "for field" << getName();
foreach(QVariant var, limit.values) { // foreach(QVariant var, limit.values) {
qDebug() << "value" << var; // qDebug() << "value" << var;
} // }
} // }
} // }
} }
bool UAVObjectField::isWithinLimits(QVariant var, quint32 index, int board) bool UAVObjectField::isWithinLimits(QVariant var, quint32 index, int board)
{ {
@ -811,43 +811,31 @@ bool UAVObjectField::isNumeric()
{ {
switch (type) { switch (type) {
case INT8: case INT8:
return true;
break;
case INT16: case INT16:
return true;
break;
case INT32: case INT32:
return true;
break;
case UINT8: case UINT8:
return true;
break;
case UINT16: case UINT16:
return true;
break;
case UINT32: case UINT32:
return true;
break;
case FLOAT32: case FLOAT32:
return true;
break;
case ENUM:
return false;
break;
case BITFIELD: case BITFIELD:
return true; return true;
break; break;
case STRING: default:
return false; return false;
}
}
bool UAVObjectField::isInteger()
{
switch (type) {
case INT8:
case INT16:
case INT32:
case UINT8:
case UINT16:
case UINT32:
return true;
break; break;
default: default:
@ -858,42 +846,7 @@ bool UAVObjectField::isNumeric()
bool UAVObjectField::isText() bool UAVObjectField::isText()
{ {
switch (type) { switch (type) {
case INT8:
return false;
break;
case INT16:
return false;
break;
case INT32:
return false;
break;
case UINT8:
return false;
break;
case UINT16:
return false;
break;
case UINT32:
return false;
break;
case FLOAT32:
return false;
break;
case ENUM: case ENUM:
return true;
break;
case BITFIELD:
return false;
break;
case STRING: case STRING:
return true; return true;

View File

@ -71,6 +71,7 @@ public:
quint32 getDataOffset(); quint32 getDataOffset();
quint32 getNumBytes(); quint32 getNumBytes();
bool isNumeric(); bool isNumeric();
bool isInteger();
bool isText(); bool isText();
QString toString(); QString toString();
void toXML(QXmlStreamWriter *xmlWriter); void toXML(QXmlStreamWriter *xmlWriter);

View File

@ -58,7 +58,7 @@ void ConfigTaskWidget::addUAVObject(QString objectName, QList<int> *reloadGroups
void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList<int> *reloadGroups) void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList<int> *reloadGroups)
{ {
addUAVObject(objectName ? objectName->getName() : QString(""), reloadGroups); addUAVObject(objectName ? objectName->getName() : QString(), reloadGroups);
} }
int ConfigTaskWidget::fieldIndexFromElementName(QString objectName, QString fieldName, QString elementName) int ConfigTaskWidget::fieldIndexFromElementName(QString objectName, QString fieldName, QString elementName)
@ -84,7 +84,7 @@ void ConfigTaskWidget::addWidgetBinding(QString objectName, QString fieldName, Q
void ConfigTaskWidget::addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, QString elementName) void ConfigTaskWidget::addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, QString elementName)
{ {
addWidgetBinding(object ? object->getName() : QString(""), field ? field->getName() : QString(""), widget, elementName); addWidgetBinding(object ? object->getName() : QString(), field ? field->getName() : QString(), widget, elementName);
} }
void ConfigTaskWidget::addWidgetBinding(QString objectName, QString fieldName, QWidget *widget, QString elementName, double scale, void ConfigTaskWidget::addWidgetBinding(QString objectName, QString fieldName, QWidget *widget, QString elementName, double scale,
@ -97,14 +97,14 @@ void ConfigTaskWidget::addWidgetBinding(QString objectName, QString fieldName, Q
void ConfigTaskWidget::addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, QString elementName, double scale, void ConfigTaskWidget::addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, QString elementName, double scale,
bool isLimited, QList<int> *reloadGroupIDs, quint32 instID) bool isLimited, QList<int> *reloadGroupIDs, quint32 instID)
{ {
addWidgetBinding(object ? object->getName() : QString(""), field ? field->getName() : QString(""), widget, elementName, scale, addWidgetBinding(object ? object->getName() : QString(), field ? field->getName() : QString(), widget, elementName, scale,
isLimited, reloadGroupIDs, instID); isLimited, reloadGroupIDs, instID);
} }
void ConfigTaskWidget::addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, int index, double scale, void ConfigTaskWidget::addWidgetBinding(UAVObject *object, UAVObjectField *field, QWidget *widget, int index, double scale,
bool isLimited, QList<int> *reloadGroupIDs, quint32 instID) bool isLimited, QList<int> *reloadGroupIDs, quint32 instID)
{ {
addWidgetBinding(object ? object->getName() : QString(""), field ? field->getName() : QString(""), widget, index, scale, addWidgetBinding(object ? object->getName() : QString(), field ? field->getName() : QString(), widget, index, scale,
isLimited, reloadGroupIDs, instID); isLimited, reloadGroupIDs, instID);
} }
@ -146,7 +146,6 @@ void ConfigTaskWidget::doAddWidgetBinding(QString objectName, QString fieldName,
binding->setIsEnabled(m_widgetBindingsPerWidget.count(widget) == 0); binding->setIsEnabled(m_widgetBindingsPerWidget.count(widget) == 0);
m_widgetBindingsPerWidget.insert(widget, binding); m_widgetBindingsPerWidget.insert(widget, binding);
if (object) { if (object) {
m_widgetBindingsPerObject.insert(object, binding); m_widgetBindingsPerObject.insert(object, binding);
if (m_saveButton) { if (m_saveButton) {
@ -183,9 +182,9 @@ void ConfigTaskWidget::setWidgetBindingObjectEnabled(QString objectName, bool en
binding->setIsEnabled(enabled); binding->setIsEnabled(enabled);
if (enabled) { if (enabled) {
if (binding->value().isValid() && !binding->value().isNull()) { if (binding->value().isValid() && !binding->value().isNull()) {
setWidgetFromVariant(binding->widget(), binding->value(), binding->scale()); setWidgetFromVariant(binding->widget(), binding->value(), binding);
} else { } else {
setWidgetFromField(binding->widget(), binding->field(), binding->index(), binding->scale(), binding->isLimited()); setWidgetFromField(binding->widget(), binding->field(), binding);
} }
} }
} }
@ -236,7 +235,8 @@ void ConfigTaskWidget::onAutopilotDisconnect()
invalidateObjects(); invalidateObjects();
} }
void ConfigTaskWidget::forceConnectedState() // dynamic widgets don't recieve the connected signal. This should be called instead. // dynamic widgets don't recieve the connected signal. This should be called instead.
void ConfigTaskWidget::forceConnectedState()
{ {
m_isConnected = true; m_isConnected = true;
setDirty(false); setDirty(false);
@ -261,7 +261,7 @@ void ConfigTaskWidget::populateWidgets()
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) { foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
if (binding->isEnabled() && binding->object() != NULL && binding->field() != NULL && binding->widget() != NULL) { if (binding->isEnabled() && binding->object() != NULL && binding->field() != NULL && binding->widget() != NULL) {
setWidgetFromField(binding->widget(), binding->field(), binding->index(), binding->scale(), binding->isLimited()); setWidgetFromField(binding->widget(), binding->field(), binding);
} }
} }
setDirty(dirtyBack); setDirty(dirtyBack);
@ -277,7 +277,7 @@ void ConfigTaskWidget::refreshWidgetsValues(UAVObject *obj)
emit refreshWidgetsValuesRequested(); emit refreshWidgetsValuesRequested();
foreach(WidgetBinding * binding, m_widgetBindingsPerObject.values(obj)) { foreach(WidgetBinding * binding, m_widgetBindingsPerObject.values(obj)) {
if (binding->isEnabled() && binding->field() != NULL && binding->widget() != NULL) { if (binding->isEnabled() && binding->field() != NULL && binding->widget() != NULL) {
setWidgetFromField(binding->widget(), binding->field(), binding->index(), binding->scale(), binding->isLimited()); setWidgetFromField(binding->widget(), binding->field(), binding);
} }
} }
setDirty(dirtyBack); setDirty(dirtyBack);
@ -357,13 +357,15 @@ void ConfigTaskWidget::forceShadowUpdates()
if (!binding->isEnabled()) { if (!binding->isEnabled()) {
continue; continue;
} }
QVariant widgetValue = getVariantFromWidget(binding->widget(), binding->scale(), binding->units()); QVariant widgetValue = getVariantFromWidget(binding->widget(), binding);
foreach(ShadowWidgetBinding * shadow, binding->shadows()) { foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
disconnectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged())); disconnectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
checkWidgetsLimits(shadow->widget(), binding->field(), binding->index(), shadow->isLimited(), widgetValue, shadow->scale()); checkWidgetsLimits(shadow->widget(), binding->field(), binding->index(), shadow->isLimited(), widgetValue, shadow->scale());
setWidgetFromVariant(shadow->widget(), widgetValue, shadow->scale());
WidgetBinding tmpBinding(shadow->widget(), binding->object(), binding->field(), binding->index(), shadow->scale(), shadow->isLimited());
setWidgetFromVariant(shadow->widget(), widgetValue, &tmpBinding);
emit widgetContentsChanged(shadow->widget()); emit widgetContentsChanged(shadow->widget());
connectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged())); connectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
@ -376,25 +378,23 @@ void ConfigTaskWidget::widgetsContentsChanged()
{ {
QWidget *emitter = ((QWidget *)sender()); QWidget *emitter = ((QWidget *)sender());
emit widgetContentsChanged(emitter); emit widgetContentsChanged(emitter);
double scale = 1.0;
QVariant value; QVariant value;
foreach(WidgetBinding * binding, m_widgetBindingsPerWidget.values(emitter)) { foreach(WidgetBinding * binding, m_widgetBindingsPerWidget.values(emitter)) {
if (binding && binding->isEnabled()) { if (binding && binding->isEnabled()) {
if (binding->widget() == emitter) { if (binding->widget() == emitter) {
scale = binding->scale(); value = getVariantFromWidget(emitter, binding);
checkWidgetsLimits(emitter, binding->field(), binding->index(), binding->isLimited(), checkWidgetsLimits(emitter, binding->field(), binding->index(), binding->isLimited(), value, binding->scale());
getVariantFromWidget(emitter, scale, binding->units()), scale);
} else { } else {
foreach(ShadowWidgetBinding * shadow, binding->shadows()) { foreach(ShadowWidgetBinding * shadow, binding->shadows()) {
if (shadow->widget() == emitter) { if (shadow->widget() == emitter) {
scale = shadow->scale(); WidgetBinding tmpBinding(shadow->widget(), binding->object(), binding->field(),
checkWidgetsLimits(emitter, binding->field(), binding->index(), shadow->isLimited(), binding->index(), shadow->scale(), shadow->isLimited());
getVariantFromWidget(emitter, scale, binding->units()), scale); value = getVariantFromWidget(emitter, &tmpBinding);
checkWidgetsLimits(emitter, binding->field(), binding->index(), shadow->isLimited(), value, shadow->scale());
} }
} }
} }
value = getVariantFromWidget(emitter, scale, binding->units());
binding->setValue(value); binding->setValue(value);
if (binding->widget() != emitter) { if (binding->widget() != emitter) {
@ -402,7 +402,7 @@ void ConfigTaskWidget::widgetsContentsChanged()
checkWidgetsLimits(binding->widget(), binding->field(), binding->index(), binding->isLimited(), checkWidgetsLimits(binding->widget(), binding->field(), binding->index(), binding->isLimited(),
value, binding->scale()); value, binding->scale());
setWidgetFromVariant(binding->widget(), value, binding->scale()); setWidgetFromVariant(binding->widget(), value, binding);
emit widgetContentsChanged(binding->widget()); emit widgetContentsChanged(binding->widget());
connectWidgetUpdatesToSlot(binding->widget(), SLOT(widgetsContentsChanged())); connectWidgetUpdatesToSlot(binding->widget(), SLOT(widgetsContentsChanged()));
@ -413,7 +413,8 @@ void ConfigTaskWidget::widgetsContentsChanged()
checkWidgetsLimits(shadow->widget(), binding->field(), binding->index(), shadow->isLimited(), checkWidgetsLimits(shadow->widget(), binding->field(), binding->index(), shadow->isLimited(),
value, shadow->scale()); value, shadow->scale());
setWidgetFromVariant(shadow->widget(), value, shadow->scale()); WidgetBinding tmp(shadow->widget(), binding->object(), binding->field(), binding->index(), shadow->scale(), shadow->isLimited());
setWidgetFromVariant(shadow->widget(), value, &tmp);
emit widgetContentsChanged(shadow->widget()); emit widgetContentsChanged(shadow->widget());
connectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged())); connectWidgetUpdatesToSlot(shadow->widget(), SLOT(widgetsContentsChanged()));
@ -708,7 +709,7 @@ void ConfigTaskWidget::defaultButtonClicked()
continue; continue;
} }
UAVDataObject *temp = ((UAVDataObject *)binding->object())->dirtyClone(); UAVDataObject *temp = ((UAVDataObject *)binding->object())->dirtyClone();
setWidgetFromField(binding->widget(), temp->getField(binding->field()->getName()), binding->index(), binding->scale(), binding->isLimited()); setWidgetFromField(binding->widget(), temp->getField(binding->field()->getName()), binding);
} }
} }
@ -751,7 +752,7 @@ void ConfigTaskWidget::reloadButtonClicked()
if (m_realtimeUpdateTimer->isActive()) { if (m_realtimeUpdateTimer->isActive()) {
binding->object()->requestUpdate(); binding->object()->requestUpdate();
if (binding->widget()) { if (binding->widget()) {
setWidgetFromField(binding->widget(), binding->field(), binding->index(), binding->scale(), binding->isLimited()); setWidgetFromField(binding->widget(), binding->field(), binding);
} }
} }
m_realtimeUpdateTimer->stop(); m_realtimeUpdateTimer->stop();
@ -823,9 +824,14 @@ void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget *widget, const char
} }
} }
QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, QString units) QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, WidgetBinding *binding)
{ {
double scale = binding->scale();
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) { if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
if (binding->isInteger()) {
return cb->currentIndex();
}
return (QString)cb->currentText(); return (QString)cb->currentText();
} else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) { } else if (QDoubleSpinBox * cb = qobject_cast<QDoubleSpinBox *>(widget)) {
return (double)(cb->value() * scale); return (double)(cb->value() * scale);
@ -837,7 +843,7 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, Q
return (QString)(cb->isChecked() ? "TRUE" : "FALSE"); return (QString)(cb->isChecked() ? "TRUE" : "FALSE");
} else if (QLineEdit * cb = qobject_cast<QLineEdit *>(widget)) { } else if (QLineEdit * cb = qobject_cast<QLineEdit *>(widget)) {
QString value = (QString)cb->displayText(); QString value = (QString)cb->displayText();
if (units == "hex") { if (binding->units() == "hex") {
bool ok; bool ok;
return value.toUInt(&ok, 16); return value.toUInt(&ok, 16);
} else { } else {
@ -848,11 +854,18 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, double scale, Q
} }
} }
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units) bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, WidgetBinding *binding)
{ {
double scale = binding->scale();
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) { if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
cb->setCurrentIndex(cb->findText(value.toString())); bool ok = true;
return true; if (binding->isInteger()) {
cb->setCurrentIndex(value.toInt(&ok));
} else {
cb->setCurrentIndex(cb->findText(value.toString()));
}
return ok;
} else if (QLabel * cb = qobject_cast<QLabel *>(widget)) { } else if (QLabel * cb = qobject_cast<QLabel *>(widget)) {
if (scale == 0) { if (scale == 0) {
cb->setText(value.toString()); cb->setText(value.toString());
@ -875,7 +888,7 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, dou
return true; return true;
} else if (QLineEdit * cb = qobject_cast<QLineEdit *>(widget)) { } else if (QLineEdit * cb = qobject_cast<QLineEdit *>(widget)) {
if ((scale == 0) || (scale == 1)) { if ((scale == 0) || (scale == 1)) {
if (units == "hex") { if (binding->units() == "hex") {
cb->setText(QString::number(value.toUInt(), 16).toUpper()); cb->setText(QString::number(value.toUInt(), 16).toUpper());
} else { } else {
cb->setText(value.toString()); cb->setText(value.toString());
@ -889,24 +902,19 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, dou
} }
} }
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale) bool ConfigTaskWidget::setWidgetFromField(QWidget *widget, UAVObjectField *field, WidgetBinding *binding)
{
return setWidgetFromVariant(widget, value, scale, QString(""));
}
bool ConfigTaskWidget::setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits)
{ {
if (!widget || !field) { if (!widget || !field) {
return false; return false;
} }
if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) { if (QComboBox * cb = qobject_cast<QComboBox *>(widget)) {
if (cb->count() == 0) { if (cb->count() == 0) {
loadWidgetLimits(cb, field, index, hasLimits, scale); loadWidgetLimits(cb, field, binding->index(), binding->isLimited(), binding->scale());
} }
} }
QVariant value = field->getValue(index); QVariant value = field->getValue(binding->index());
checkWidgetsLimits(widget, field, index, hasLimits, value, scale); checkWidgetsLimits(widget, field, binding->index(), binding->isLimited(), value, binding->scale());
bool result = setWidgetFromVariant(widget, value, scale, field->getUnits()); bool result = setWidgetFromVariant(widget, value, binding);
if (result) { if (result) {
return true; return true;
} else { } else {
@ -1070,7 +1078,23 @@ QString WidgetBinding::units() const
if (m_field) { if (m_field) {
return m_field->getUnits(); return m_field->getUnits();
} }
return QString(""); return QString();
}
QString WidgetBinding::type() const
{
if (m_field) {
return m_field->getTypeAsString();
}
return QString();
}
bool WidgetBinding::isInteger() const
{
if (m_field) {
return m_field->isInteger();
}
return false;
} }
UAVObject *WidgetBinding::object() const UAVObject *WidgetBinding::object() const

View File

@ -69,6 +69,8 @@ public:
~WidgetBinding(); ~WidgetBinding();
QString units() const; QString units() const;
QString type() const;
bool isInteger() const;
UAVObject *object() const; UAVObject *object() const;
UAVObjectField *field() const; UAVObjectField *field() const;
int index() const; int index() const;
@ -219,11 +221,10 @@ private:
QString m_outOfLimitsStyle; QString m_outOfLimitsStyle;
QTimer *m_realtimeUpdateTimer; QTimer *m_realtimeUpdateTimer;
bool setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits); bool setWidgetFromField(QWidget *widget, UAVObjectField *field, WidgetBinding *binding);
QVariant getVariantFromWidget(QWidget *widget, double scale, const QString units); QVariant getVariantFromWidget(QWidget *widget, WidgetBinding *binding);
bool setWidgetFromVariant(QWidget *widget, QVariant value, double scale, QString units); bool setWidgetFromVariant(QWidget *widget, QVariant value, WidgetBinding *binding);
bool setWidgetFromVariant(QWidget *widget, QVariant value, double scale);
void connectWidgetUpdatesToSlot(QWidget *widget, const char *function); void connectWidgetUpdatesToSlot(QWidget *widget, const char *function);
void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function); void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function);

View File

@ -46,15 +46,14 @@ SOURCES += uploadergadget.cpp \
SSP/qsspt.cpp \ SSP/qsspt.cpp \
runningdevicewidget.cpp runningdevicewidget.cpp
OTHER_FILES += Uploader.pluginspec \ OTHER_FILES += Uploader.pluginspec
FORMS += \ FORMS += \
uploader.ui \ uploader.ui \
devicewidget.ui \ devicewidget.ui \
runningdevicewidget.ui runningdevicewidget.ui
RESOURCES += \ RESOURCES += uploader.qrc
uploader.qrc
exists( ../../../../../build/openpilotgcs-synthetics/opfw_resource.qrc ) { exists( ../../../../../build/openpilotgcs-synthetics/opfw_resource.qrc ) {
RESOURCES += ../../../../../build/openpilotgcs-synthetics/opfw_resource.qrc RESOURCES += ../../../../../build/openpilotgcs-synthetics/opfw_resource.qrc

View File

@ -99,7 +99,7 @@ SRC += $(PIOSCOMMON)/pios_usb_util.c
## PIOS system code ## PIOS system code
SRC += $(PIOSCOMMON)/pios_task_monitor.c SRC += $(PIOSCOMMON)/pios_task_monitor.c
SRC += $(PIOSCOMMON)/pios_callbackscheduler.c SRC += $(PIOSCOMMON)/pios_callbackscheduler.c
SRC += $(PIOSCOMMON)/pios_notify.c
## Misc library functions ## Misc library functions
SRC += $(FLIGHTLIB)/fifo_buffer.c SRC += $(FLIGHTLIB)/fifo_buffer.c
SRC += $(FLIGHTLIB)/sanitycheck.c SRC += $(FLIGHTLIB)/sanitycheck.c

View File

@ -4,7 +4,7 @@
<field name="SamplePeriod" units="ms" type="uint8" elements="1" defaultvalue="100"/> <field name="SamplePeriod" units="ms" type="uint8" elements="1" defaultvalue="100"/>
<field name="ZeroPoint" units="raw" type="uint16" elements="1" defaultvalue="0"/> <field name="ZeroPoint" units="raw" type="uint16" elements="1" defaultvalue="0"/>
<field name="Scale" units="raw" type="float" elements="1" defaultvalue="1.0"/> <field name="Scale" units="raw" type="float" elements="1" defaultvalue="1.0"/>
<field name="AirspeedSensorType" units="" type="enum" elements="1" options="PixHawkAirspeedMS4525DO,EagleTreeAirspeedV3,DIYDronesMPXV5004,DIYDronesMPXV7002,GroundSpeedBasedWindEstimation,None" defaultvalue="GroundSpeedBasedWindEstimation"/> <field name="AirspeedSensorType" units="" type="enum" elements="1" options="PixHawkAirspeedMS4525DO,EagleTreeAirspeedV3,DIYDronesMPXV5004,DIYDronesMPXV7002,GroundSpeedBasedWindEstimation,None" defaultvalue="None"/>
<field name="GroundSpeedBasedEstimationLowPassAlpha" units="" type="float" elements="1" defaultvalue="0.08" /> <field name="GroundSpeedBasedEstimationLowPassAlpha" units="" type="float" elements="1" defaultvalue="0.08" />
<access gcs="readwrite" flight="readwrite"/> <access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/> <telemetrygcs acked="true" updatemode="onchange" period="0"/>

View File

@ -25,6 +25,7 @@
<field name="OptionalModules" units="" type="enum" elementnames="CameraStab,GPS,ComUsbBridge,Fault,Altitude,Airspeed,TxPID,Autotune,VtolPathFollower,FixedWingPathFollower,Battery,Overo,MagBaro,OsdHk" options="Disabled,Enabled" defaultvalue="Disabled"/> <field name="OptionalModules" units="" type="enum" elementnames="CameraStab,GPS,ComUsbBridge,Fault,Altitude,Airspeed,TxPID,Autotune,VtolPathFollower,FixedWingPathFollower,Battery,Overo,MagBaro,OsdHk" options="Disabled,Enabled" defaultvalue="Disabled"/>
<field name="ADCRouting" units="" type="enum" elementnames="adc0,adc1,adc2,adc3" options="Disabled,BatteryVoltage,BatteryCurrent,AnalogAirspeed,Generic" defaultvalue="Disabled"/> <field name="ADCRouting" units="" type="enum" elementnames="adc0,adc1,adc2,adc3" options="Disabled,BatteryVoltage,BatteryCurrent,AnalogAirspeed,Generic" defaultvalue="Disabled"/>
<field name="DSMxBind" units="" type="uint8" elements="1" defaultvalue="0"/> <field name="DSMxBind" units="" type="uint8" elements="1" defaultvalue="0"/>
<field name="WS2811LED_Out" units="" type="enum" elements="1" options="ServoOut1,ServoOut2,ServoOut3,ServoOut4,ServoOut5,ServoOut6,FlexiPin3,FlexiPin4,Disabled" defaultvalue="Disabled" />
<access gcs="readwrite" flight="readwrite"/> <access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/> <telemetrygcs acked="true" updatemode="onchange" period="0"/>