mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-18 03:52:11 +01:00
Merge branch 'next' into amorale/OP-911_mpu6000_fix_isr
This commit is contained in:
commit
594b44118f
@ -28,7 +28,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "openpilot.h"
|
#include "openpilot.h"
|
||||||
#include "alarms.h"
|
#include "inc/alarms.h"
|
||||||
|
|
||||||
// Private constants
|
// Private constants
|
||||||
|
|
||||||
@ -46,12 +46,12 @@ static int32_t hasSeverity(SystemAlarmsAlarmOptions severity);
|
|||||||
int32_t AlarmsInitialize(void)
|
int32_t AlarmsInitialize(void)
|
||||||
{
|
{
|
||||||
SystemAlarmsInitialize();
|
SystemAlarmsInitialize();
|
||||||
|
|
||||||
lock = xSemaphoreCreateRecursiveMutex();
|
lock = xSemaphoreCreateRecursiveMutex();
|
||||||
//do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that
|
//do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that
|
||||||
//AlarmsClearAll();
|
//AlarmsClearAll();
|
||||||
//AlarmsDefaultAll();
|
//AlarmsDefaultAll();
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -62,23 +62,21 @@ int32_t AlarmsInitialize(void)
|
|||||||
*/
|
*/
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
||||||
{
|
{
|
||||||
SystemAlarmsData alarms;
|
SystemAlarmsData alarms;
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
// Check that this is a valid alarm
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) {
|
||||||
{
|
return -1;
|
||||||
return -1;
|
}
|
||||||
}
|
|
||||||
|
|
||||||
// Lock
|
// Lock
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||||
|
|
||||||
// Read alarm and update its severity only if it was changed
|
// Read alarm and update its severity only if it was changed
|
||||||
SystemAlarmsGet(&alarms);
|
SystemAlarmsGet(&alarms);
|
||||||
if ( alarms.Alarm[alarm] != severity )
|
if (alarms.Alarm[alarm] != severity) {
|
||||||
{
|
alarms.Alarm[alarm] = severity;
|
||||||
alarms.Alarm[alarm] = severity;
|
SystemAlarmsSet(&alarms);
|
||||||
SystemAlarmsSet(&alarms);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Release lock
|
// Release lock
|
||||||
@ -87,6 +85,43 @@ int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set an Extended Alarm
|
||||||
|
* @param alarm The system alarm to be modified
|
||||||
|
* @param severity The alarm severity
|
||||||
|
* @param status The Extended alarm status field
|
||||||
|
* @param subStatus The Extended alarm substatus field
|
||||||
|
* @return 0 if success, -1 if an error
|
||||||
|
*/
|
||||||
|
int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm,
|
||||||
|
SystemAlarmsAlarmOptions severity,
|
||||||
|
SystemAlarmsExtendedAlarmStatusOptions status,
|
||||||
|
uint8_t subStatus)
|
||||||
|
{
|
||||||
|
SystemAlarmsData alarms;
|
||||||
|
|
||||||
|
// Check that this is a valid alarm
|
||||||
|
if (alarm >= SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM) {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Lock
|
||||||
|
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||||
|
|
||||||
|
// Read alarm and update its severity only if it was changed
|
||||||
|
SystemAlarmsGet(&alarms);
|
||||||
|
if (alarms.Alarm[alarm] != severity) {
|
||||||
|
alarms.ExtendedAlarmStatus[alarm] = status;
|
||||||
|
alarms.ExtendedAlarmSubStatus[alarm] = subStatus;
|
||||||
|
alarms.Alarm[alarm] = severity;
|
||||||
|
SystemAlarmsSet(&alarms);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Release lock
|
||||||
|
xSemaphoreGiveRecursive(lock);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Get an alarm
|
* Get an alarm
|
||||||
* @param alarm The system alarm to be read
|
* @param alarm The system alarm to be read
|
||||||
@ -94,13 +129,12 @@ int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity
|
|||||||
*/
|
*/
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
||||||
{
|
{
|
||||||
SystemAlarmsData alarms;
|
SystemAlarmsData alarms;
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
// Check that this is a valid alarm
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) {
|
||||||
{
|
return 0;
|
||||||
return 0;
|
}
|
||||||
}
|
|
||||||
|
|
||||||
// Read alarm
|
// Read alarm
|
||||||
SystemAlarmsGet(&alarms);
|
SystemAlarmsGet(&alarms);
|
||||||
@ -114,7 +148,7 @@ SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
|||||||
*/
|
*/
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm)
|
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm)
|
||||||
{
|
{
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT);
|
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -122,10 +156,8 @@ int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm)
|
|||||||
*/
|
*/
|
||||||
void AlarmsDefaultAll()
|
void AlarmsDefaultAll()
|
||||||
{
|
{
|
||||||
uint32_t n;
|
for (uint32_t n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) {
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
AlarmsDefault(n);
|
||||||
{
|
|
||||||
AlarmsDefault(n);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -136,7 +168,11 @@ void AlarmsDefaultAll()
|
|||||||
*/
|
*/
|
||||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm)
|
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm)
|
||||||
{
|
{
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK);
|
if (alarm < SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM) {
|
||||||
|
return ExtendedAlarmsSet(alarm, SYSTEMALARMS_ALARM_OK, SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE, 0);
|
||||||
|
} else {
|
||||||
|
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -144,10 +180,8 @@ int32_t AlarmsClear(SystemAlarmsAlarmElem alarm)
|
|||||||
*/
|
*/
|
||||||
void AlarmsClearAll()
|
void AlarmsClearAll()
|
||||||
{
|
{
|
||||||
uint32_t n;
|
for (uint32_t n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) {
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
AlarmsClear(n);
|
||||||
{
|
|
||||||
AlarmsClear(n);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -157,7 +191,7 @@ void AlarmsClearAll()
|
|||||||
*/
|
*/
|
||||||
int32_t AlarmsHasWarnings()
|
int32_t AlarmsHasWarnings()
|
||||||
{
|
{
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_WARNING);
|
return hasSeverity(SYSTEMALARMS_ALARM_WARNING);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -166,8 +200,9 @@ int32_t AlarmsHasWarnings()
|
|||||||
*/
|
*/
|
||||||
int32_t AlarmsHasErrors()
|
int32_t AlarmsHasErrors()
|
||||||
{
|
{
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_ERROR);
|
return hasSeverity(SYSTEMALARMS_ALARM_ERROR);
|
||||||
};
|
}
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Check if there are any alarms with critical or higher severity
|
* Check if there are any alarms with critical or higher severity
|
||||||
@ -175,8 +210,9 @@ int32_t AlarmsHasErrors()
|
|||||||
*/
|
*/
|
||||||
int32_t AlarmsHasCritical()
|
int32_t AlarmsHasCritical()
|
||||||
{
|
{
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL);
|
return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL);
|
||||||
};
|
}
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Check if there are any alarms with the given or higher severity
|
* Check if there are any alarms with the given or higher severity
|
||||||
@ -184,31 +220,28 @@ int32_t AlarmsHasCritical()
|
|||||||
*/
|
*/
|
||||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
||||||
{
|
{
|
||||||
SystemAlarmsData alarms;
|
SystemAlarmsData alarms;
|
||||||
uint32_t n;
|
|
||||||
|
|
||||||
// Lock
|
// Lock
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||||
|
|
||||||
// Read alarms
|
// Read alarms
|
||||||
SystemAlarmsGet(&alarms);
|
SystemAlarmsGet(&alarms);
|
||||||
|
|
||||||
// Go through alarms and check if any are of the given severity or higher
|
// Go through alarms and check if any are of the given severity or higher
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
for (uint32_t n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) {
|
||||||
{
|
if (alarms.Alarm[n] >= severity) {
|
||||||
if ( alarms.Alarm[n] >= severity)
|
xSemaphoreGiveRecursive(lock);
|
||||||
{
|
return 1;
|
||||||
xSemaphoreGiveRecursive(lock);
|
}
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// If this point is reached then no alarms found
|
// If this point is reached then no alarms found
|
||||||
xSemaphoreGiveRecursive(lock);
|
xSemaphoreGiveRecursive(lock);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
|
4
flight/targets/PipXtreme/System/inc/alarms.h → flight/Libraries/inc/alarms.h
Executable file → Normal file
4
flight/targets/PipXtreme/System/inc/alarms.h → flight/Libraries/inc/alarms.h
Executable file → Normal file
@ -33,6 +33,10 @@
|
|||||||
|
|
||||||
int32_t AlarmsInitialize(void);
|
int32_t AlarmsInitialize(void);
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity);
|
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity);
|
||||||
|
int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm,
|
||||||
|
SystemAlarmsAlarmOptions severity,
|
||||||
|
SystemAlarmsExtendedAlarmStatusOptions status,
|
||||||
|
uint8_t subStatus);
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm);
|
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm);
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm);
|
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm);
|
||||||
void AlarmsDefaultAll();
|
void AlarmsDefaultAll();
|
@ -26,9 +26,22 @@
|
|||||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <systemalarms.h>
|
||||||
|
|
||||||
#ifndef SANITYCHECK_H
|
#ifndef SANITYCHECK_H
|
||||||
#define SANITYCHECK_H
|
#define SANITYCHECK_H
|
||||||
|
|
||||||
|
#define SANITYCHECK_STATUS_ERROR_NONE SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE
|
||||||
|
#define SANITYCHECK_STATUS_ERROR_FLIGHTMODE SYSTEMALARMS_EXTENDEDALARMSTATUS_FLIGHTMODE
|
||||||
|
|
||||||
|
#define BOOTFAULT_STATUS_ERROR_NONE SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE
|
||||||
|
#define BOOTFAULT_STATUS_ERROR_REQUIRE_REBOOT SYSTEMALARMS_EXTENDEDALARMSTATUS_REBOOTREQUIRED
|
||||||
|
|
||||||
|
#if (SYSTEMALARMS_EXTENDEDALARMSTATUS_NUMELEM != SYSTEMALARMS_EXTENDEDALARMSUBSTATUS_NUMELEM) || \
|
||||||
|
(SYSTEMALARMS_EXTENDEDALARMSUBSTATUS_NUMELEM > SYSTEMALARMS_ALARM_NUMELEM)
|
||||||
|
#error Incongruent SystemAlarms. Please revise the UAVO definition in systemalarms.xml
|
||||||
|
#endif
|
||||||
|
|
||||||
extern int32_t configuration_check();
|
extern int32_t configuration_check();
|
||||||
|
|
||||||
#endif /* SANITYCHECK_H */
|
#endif /* SANITYCHECK_H */
|
||||||
|
@ -26,13 +26,16 @@
|
|||||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "openpilot.h"
|
#include <openpilot.h>
|
||||||
#include "taskmonitor.h"
|
|
||||||
#include <pios_board_info.h>
|
#include <pios_board_info.h>
|
||||||
#include "sanitycheck.h"
|
|
||||||
#include "manualcontrolsettings.h"
|
// Private includes
|
||||||
#include "systemalarms.h"
|
#include "inc/taskmonitor.h"
|
||||||
#include "systemsettings.h"
|
#include "inc/sanitycheck.h"
|
||||||
|
|
||||||
|
// UAVOs
|
||||||
|
#include <manualcontrolsettings.h>
|
||||||
|
#include <systemsettings.h>
|
||||||
|
|
||||||
/****************************
|
/****************************
|
||||||
* Current checks:
|
* Current checks:
|
||||||
@ -49,98 +52,101 @@ static int32_t check_stabilization_settings(int index, bool multirotor);
|
|||||||
*/
|
*/
|
||||||
int32_t configuration_check()
|
int32_t configuration_check()
|
||||||
{
|
{
|
||||||
int32_t status = SYSTEMALARMS_ALARM_OK;
|
int32_t severity = SYSTEMALARMS_ALARM_OK;
|
||||||
|
SystemAlarmsExtendedAlarmStatusOptions alarmstatus = SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE;
|
||||||
|
uint8_t alarmsubstatus = 0;
|
||||||
|
// Get board type
|
||||||
|
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||||
|
bool coptercontrol = bdinfo->board_type == 0x04;
|
||||||
|
|
||||||
// Get board type
|
// Classify airframe type
|
||||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
bool multirotor = true;
|
||||||
bool coptercontrol = bdinfo->board_type == 0x04;
|
uint8_t airframe_type;
|
||||||
|
SystemSettingsAirframeTypeGet(&airframe_type);
|
||||||
|
switch(airframe_type) {
|
||||||
|
case SYSTEMSETTINGS_AIRFRAMETYPE_QUADX:
|
||||||
|
case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP:
|
||||||
|
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA:
|
||||||
|
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO:
|
||||||
|
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX:
|
||||||
|
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV:
|
||||||
|
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXP:
|
||||||
|
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXACOAX:
|
||||||
|
case SYSTEMSETTINGS_AIRFRAMETYPE_TRI:
|
||||||
|
multirotor = true;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
multirotor = false;
|
||||||
|
}
|
||||||
|
|
||||||
// Classify airframe type
|
// For each available flight mode position sanity check the available
|
||||||
bool multirotor = true;
|
// modes
|
||||||
uint8_t airframe_type;
|
uint8_t num_modes;
|
||||||
SystemSettingsAirframeTypeGet(&airframe_type);
|
uint8_t modes[MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_NUMELEM];
|
||||||
switch(airframe_type) {
|
ManualControlSettingsFlightModeNumberGet(&num_modes);
|
||||||
case SYSTEMSETTINGS_AIRFRAMETYPE_QUADX:
|
ManualControlSettingsFlightModePositionGet(modes);
|
||||||
case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP:
|
|
||||||
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA:
|
|
||||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO:
|
|
||||||
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX:
|
|
||||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV:
|
|
||||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXP:
|
|
||||||
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXACOAX:
|
|
||||||
case SYSTEMSETTINGS_AIRFRAMETYPE_TRI:
|
|
||||||
multirotor = true;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
multirotor = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// For each available flight mode position sanity check the available
|
for(uint32_t i = 0; i < num_modes; i++) {
|
||||||
// modes
|
switch(modes[i]) {
|
||||||
uint8_t num_modes;
|
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MANUAL:
|
||||||
uint8_t modes[MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_NUMELEM];
|
if (multirotor) {
|
||||||
ManualControlSettingsFlightModeNumberGet(&num_modes);
|
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||||
ManualControlSettingsFlightModePositionGet(modes);
|
}
|
||||||
|
break;
|
||||||
|
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1:
|
||||||
|
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor) : severity;
|
||||||
|
break;
|
||||||
|
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2:
|
||||||
|
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor) : severity;
|
||||||
|
break;
|
||||||
|
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3:
|
||||||
|
severity = (severity == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : severity;
|
||||||
|
break;
|
||||||
|
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_AUTOTUNE:
|
||||||
|
if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_AUTOTUNE)) {
|
||||||
|
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD:
|
||||||
|
if (coptercontrol) {
|
||||||
|
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||||
|
} else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_ALTITUDEHOLD)) { // Revo supports altitude hold
|
||||||
|
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL:
|
||||||
|
if (coptercontrol) {
|
||||||
|
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||||
|
} else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) { // Revo supports altitude hold
|
||||||
|
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD:
|
||||||
|
if (coptercontrol){
|
||||||
|
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||||
|
} else if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) { // Revo supports altitude hold
|
||||||
|
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
// Uncovered modes are automatically an error
|
||||||
|
severity = SYSTEMALARMS_ALARM_ERROR;
|
||||||
|
}
|
||||||
|
// mark the first encountered erroneous setting in status and substatus
|
||||||
|
if ((severity != SYSTEMALARMS_ALARM_OK) && (alarmstatus == SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE)) {
|
||||||
|
alarmstatus = SYSTEMALARMS_EXTENDEDALARMSTATUS_FLIGHTMODE;
|
||||||
|
alarmsubstatus = i;
|
||||||
|
}
|
||||||
|
|
||||||
for(uint32_t i = 0; i < num_modes; i++) {
|
}
|
||||||
switch(modes[i]) {
|
|
||||||
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MANUAL:
|
|
||||||
if (multirotor)
|
|
||||||
status = SYSTEMALARMS_ALARM_ERROR;
|
|
||||||
break;
|
|
||||||
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1:
|
|
||||||
status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(1, multirotor) : status;
|
|
||||||
break;
|
|
||||||
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2:
|
|
||||||
status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(2, multirotor) : status;
|
|
||||||
break;
|
|
||||||
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3:
|
|
||||||
status = (status == SYSTEMALARMS_ALARM_OK) ? check_stabilization_settings(3, multirotor) : status;
|
|
||||||
break;
|
|
||||||
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_AUTOTUNE:
|
|
||||||
if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_AUTOTUNE))
|
|
||||||
status = SYSTEMALARMS_ALARM_ERROR;
|
|
||||||
break;
|
|
||||||
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD:
|
|
||||||
if (coptercontrol)
|
|
||||||
status = SYSTEMALARMS_ALARM_ERROR;
|
|
||||||
else {
|
|
||||||
// Revo supports altitude hold
|
|
||||||
if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_ALTITUDEHOLD))
|
|
||||||
status = SYSTEMALARMS_ALARM_ERROR;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL:
|
|
||||||
if (coptercontrol)
|
|
||||||
status = SYSTEMALARMS_ALARM_ERROR;
|
|
||||||
else {
|
|
||||||
// Revo supports altitude hold
|
|
||||||
if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER))
|
|
||||||
status = SYSTEMALARMS_ALARM_ERROR;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD:
|
|
||||||
if (coptercontrol)
|
|
||||||
status = SYSTEMALARMS_ALARM_ERROR;
|
|
||||||
else {
|
|
||||||
// Revo supports altitude hold
|
|
||||||
if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER))
|
|
||||||
status = SYSTEMALARMS_ALARM_ERROR;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
// Uncovered modes are automatically an error
|
|
||||||
status = SYSTEMALARMS_ALARM_ERROR;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// TODO: Check on a multirotor no axis supports "None"
|
// TODO: Check on a multirotor no axis supports "None"
|
||||||
if(status != SYSTEMALARMS_ALARM_OK)
|
if(severity != SYSTEMALARMS_ALARM_OK)
|
||||||
AlarmsSet(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION, status);
|
ExtendedAlarmsSet(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION, severity, alarmstatus, alarmsubstatus);
|
||||||
else
|
else
|
||||||
AlarmsClear(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION);
|
AlarmsClear(SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION);
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -151,39 +157,39 @@ int32_t configuration_check()
|
|||||||
*/
|
*/
|
||||||
static int32_t check_stabilization_settings(int index, bool multirotor)
|
static int32_t check_stabilization_settings(int index, bool multirotor)
|
||||||
{
|
{
|
||||||
// Make sure the modes have identical sizes
|
// Make sure the modes have identical sizes
|
||||||
if (MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_NUMELEM ||
|
if (MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_NUMELEM ||
|
||||||
MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_NUMELEM)
|
MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM != MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_NUMELEM)
|
||||||
return SYSTEMALARMS_ALARM_ERROR;
|
return SYSTEMALARMS_ALARM_ERROR;
|
||||||
|
|
||||||
uint8_t modes[MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM];
|
uint8_t modes[MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NUMELEM];
|
||||||
|
|
||||||
// Get the different axis modes for this switch position
|
// Get the different axis modes for this switch position
|
||||||
switch(index) {
|
switch(index) {
|
||||||
case 1:
|
case 1:
|
||||||
ManualControlSettingsStabilization1SettingsGet(modes);
|
ManualControlSettingsStabilization1SettingsGet(modes);
|
||||||
break;
|
break;
|
||||||
case 2:
|
case 2:
|
||||||
ManualControlSettingsStabilization2SettingsGet(modes);
|
ManualControlSettingsStabilization2SettingsGet(modes);
|
||||||
break;
|
break;
|
||||||
case 3:
|
case 3:
|
||||||
ManualControlSettingsStabilization3SettingsGet(modes);
|
ManualControlSettingsStabilization3SettingsGet(modes);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
return SYSTEMALARMS_ALARM_ERROR;
|
return SYSTEMALARMS_ALARM_ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
// For multirotors verify that nothing is set to "none"
|
// For multirotors verify that nothing is set to "none"
|
||||||
if (multirotor) {
|
if (multirotor) {
|
||||||
for(uint32_t i = 0; i < NELEMENTS(modes); i++) {
|
for(uint32_t i = 0; i < NELEMENTS(modes); i++) {
|
||||||
if (modes[i] == MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE)
|
if (modes[i] == MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE)
|
||||||
return SYSTEMALARMS_ALARM_ERROR;
|
return SYSTEMALARMS_ALARM_ERROR;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Warning: This assumes that certain conditions in the XML file are met. That
|
// Warning: This assumes that certain conditions in the XML file are met. That
|
||||||
// MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE has the same numeric value for each channel
|
// MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE has the same numeric value for each channel
|
||||||
// and is the same for STABILIZATIONDESIRED_STABILIZATIONMODE_NONE
|
// and is the same for STABILIZATIONDESIRED_STABILIZATIONMODE_NONE
|
||||||
|
|
||||||
return SYSTEMALARMS_ALARM_OK;
|
return SYSTEMALARMS_ALARM_OK;
|
||||||
}
|
}
|
||||||
|
@ -218,14 +218,14 @@ static void AttitudeTask(void *parameters)
|
|||||||
// For first 7 seconds use accels to get gyro bias
|
// For first 7 seconds use accels to get gyro bias
|
||||||
accelKp = 1;
|
accelKp = 1;
|
||||||
accelKi = 0.9;
|
accelKi = 0.9;
|
||||||
yawBiasRate = 0.23;
|
yawBiasRate = 0.01;
|
||||||
accel_filter_enabled = false;
|
accel_filter_enabled = false;
|
||||||
init = 0;
|
init = 0;
|
||||||
}
|
}
|
||||||
else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) {
|
else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) {
|
||||||
accelKp = 1;
|
accelKp = 1;
|
||||||
accelKi = 0.9;
|
accelKi = 0.9;
|
||||||
yawBiasRate = 0.23;
|
yawBiasRate = 0.01;
|
||||||
accel_filter_enabled = false;
|
accel_filter_enabled = false;
|
||||||
init = 0;
|
init = 0;
|
||||||
} else if (init == 0) {
|
} else if (init == 0) {
|
||||||
|
@ -38,17 +38,25 @@
|
|||||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "openpilot.h"
|
#include <openpilot.h>
|
||||||
#include "systemmod.h"
|
|
||||||
#include "objectpersistence.h"
|
// private includes
|
||||||
#include "flightstatus.h"
|
#include "inc/systemmod.h"
|
||||||
#include "systemstats.h"
|
|
||||||
#include "systemsettings.h"
|
// UAVOs
|
||||||
#include "i2cstats.h"
|
#include <objectpersistence.h>
|
||||||
#include "taskinfo.h"
|
#include <flightstatus.h>
|
||||||
#include "watchdogstatus.h"
|
#include <systemstats.h>
|
||||||
#include "taskmonitor.h"
|
#include <systemsettings.h>
|
||||||
#include "hwsettings.h"
|
#include <i2cstats.h>
|
||||||
|
#include <taskinfo.h>
|
||||||
|
#include <watchdogstatus.h>
|
||||||
|
#include <taskmonitor.h>
|
||||||
|
#include <hwsettings.h>
|
||||||
|
|
||||||
|
// Flight Libraries
|
||||||
|
#include <sanitycheck.h>
|
||||||
|
|
||||||
|
|
||||||
//#define DEBUG_THIS_FILE
|
//#define DEBUG_THIS_FILE
|
||||||
|
|
||||||
@ -64,8 +72,8 @@
|
|||||||
|
|
||||||
#ifndef IDLE_COUNTS_PER_SEC_AT_NO_LOAD
|
#ifndef IDLE_COUNTS_PER_SEC_AT_NO_LOAD
|
||||||
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 995998 // calibrated by running tests/test_cpuload.c
|
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 995998 // calibrated by running tests/test_cpuload.c
|
||||||
// must be updated if the FreeRTOS or compiler
|
// must be updated if the FreeRTOS or compiler
|
||||||
// optimisation options are changed.
|
// optimisation options are changed.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(PIOS_SYSTEM_STACK_SIZE)
|
#if defined(PIOS_SYSTEM_STACK_SIZE)
|
||||||
@ -85,6 +93,7 @@ static xTaskHandle systemTaskHandle;
|
|||||||
static xQueueHandle objectPersistenceQueue;
|
static xQueueHandle objectPersistenceQueue;
|
||||||
static bool stackOverflow;
|
static bool stackOverflow;
|
||||||
static bool mallocFailed;
|
static bool mallocFailed;
|
||||||
|
static HwSettingsData bootHwSettings;
|
||||||
|
|
||||||
// Private functions
|
// Private functions
|
||||||
static void objectUpdatedCb(UAVObjEvent * ev);
|
static void objectUpdatedCb(UAVObjEvent * ev);
|
||||||
@ -171,6 +180,8 @@ static void systemTask(void *parameters)
|
|||||||
// Listen for SettingPersistance object updates, connect a callback function
|
// Listen for SettingPersistance object updates, connect a callback function
|
||||||
ObjectPersistenceConnectQueue(objectPersistenceQueue);
|
ObjectPersistenceConnectQueue(objectPersistenceQueue);
|
||||||
|
|
||||||
|
// Load a copy of HwSetting active at boot time
|
||||||
|
HwSettingsGet(&bootHwSettings);
|
||||||
// Whenever the configuration changes, make sure it is safe to fly
|
// Whenever the configuration changes, make sure it is safe to fly
|
||||||
HwSettingsConnectCallback(hwSettingsUpdatedCb);
|
HwSettingsConnectCallback(hwSettingsUpdatedCb);
|
||||||
|
|
||||||
@ -303,9 +314,10 @@ static void objectUpdatedCb(UAVObjEvent * ev)
|
|||||||
retval = UAVObjDeleteMetaobjects();
|
retval = UAVObjDeleteMetaobjects();
|
||||||
}
|
}
|
||||||
} else if (objper.Operation == OBJECTPERSISTENCE_OPERATION_FULLERASE) {
|
} else if (objper.Operation == OBJECTPERSISTENCE_OPERATION_FULLERASE) {
|
||||||
retval = -1;
|
|
||||||
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
|
#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS)
|
||||||
retval = PIOS_FLASHFS_Format(0);
|
retval = PIOS_FLASHFS_Format(0);
|
||||||
|
#else
|
||||||
|
retval = -1;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
switch(retval) {
|
switch(retval) {
|
||||||
@ -328,7 +340,12 @@ static void objectUpdatedCb(UAVObjEvent * ev)
|
|||||||
*/
|
*/
|
||||||
static void hwSettingsUpdatedCb(UAVObjEvent * ev)
|
static void hwSettingsUpdatedCb(UAVObjEvent * ev)
|
||||||
{
|
{
|
||||||
AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT,SYSTEMALARMS_ALARM_ERROR);
|
HwSettingsData currentHwSettings;
|
||||||
|
HwSettingsGet(¤tHwSettings);
|
||||||
|
// check whether the Hw Configuration has changed from the one used at boot time
|
||||||
|
if (memcmp(&bootHwSettings, ¤tHwSettings, sizeof(HwSettingsData)) != 0) {
|
||||||
|
ExtendedAlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_ERROR, SYSTEMALARMS_EXTENDEDALARMSTATUS_REBOOTREQUIRED, 0);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -11,7 +11,7 @@ ifeq ($(USE_DSP_LIB), YES)
|
|||||||
CMSIS_DSPLIB := $(CMSIS2_DIR)DSP_Lib/Source
|
CMSIS_DSPLIB := $(CMSIS2_DIR)DSP_Lib/Source
|
||||||
|
|
||||||
# Compile all files into output directory
|
# Compile all files into output directory
|
||||||
DSPLIB_SRC := $(wildcard $(CMSIS_DSPLIB)/*/*.c)
|
DSPLIB_SRC := $(sort $(wildcard $(CMSIS_DSPLIB)/*/*.c))
|
||||||
DSPLIB_SRCBASE := $(notdir $(basename $(DSPLIB_SRC)))
|
DSPLIB_SRCBASE := $(notdir $(basename $(DSPLIB_SRC)))
|
||||||
$(foreach src, $(DSPLIB_SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src))))
|
$(foreach src, $(DSPLIB_SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src))))
|
||||||
|
|
||||||
|
@ -6,5 +6,5 @@
|
|||||||
#
|
#
|
||||||
|
|
||||||
FREERTOS_DIR := $(dir $(lastword $(MAKEFILE_LIST)))/Source
|
FREERTOS_DIR := $(dir $(lastword $(MAKEFILE_LIST)))/Source
|
||||||
SRC += $(wildcard $(FREERTOS_DIR)/*.c)
|
SRC += $(sort $(wildcard $(FREERTOS_DIR)/*.c))
|
||||||
EXTRAINCDIRS += $(FREERTOS_DIR)/include
|
EXTRAINCDIRS += $(FREERTOS_DIR)/include
|
||||||
|
@ -3,5 +3,5 @@
|
|||||||
#
|
#
|
||||||
|
|
||||||
DOSFS_DIR := $(dir $(lastword $(MAKEFILE_LIST)))
|
DOSFS_DIR := $(dir $(lastword $(MAKEFILE_LIST)))
|
||||||
SRC += $(wildcard $(DOSFS_DIR)*.c)
|
SRC += $(sort $(wildcard $(DOSFS_DIR)*.c))
|
||||||
EXTRAINCDIRS += $(DOSFS_DIR)
|
EXTRAINCDIRS += $(DOSFS_DIR)
|
||||||
|
@ -3,5 +3,5 @@
|
|||||||
#
|
#
|
||||||
|
|
||||||
MSHEAP_DIR := $(dir $(lastword $(MAKEFILE_LIST)))
|
MSHEAP_DIR := $(dir $(lastword $(MAKEFILE_LIST)))
|
||||||
SRC += $(wildcard $(MSHEAP_DIR)*.c)
|
SRC += $(sort $(wildcard $(MSHEAP_DIR)*.c))
|
||||||
EXTRAINCDIRS += $(MSHEAP_DIR)
|
EXTRAINCDIRS += $(MSHEAP_DIR)
|
||||||
|
@ -122,6 +122,11 @@ extern int32_t PIOS_GCSRCVR_Init(uint32_t *gcsrcvr_id)
|
|||||||
if (!gcsrcvr_dev)
|
if (!gcsrcvr_dev)
|
||||||
return -1;
|
return -1;
|
||||||
|
|
||||||
|
for (uint8_t i = 0; i < GCSRECEIVER_CHANNEL_NUMELEM; i++) {
|
||||||
|
/* Flush channels */
|
||||||
|
gcsreceiverdata.Channel[i] = PIOS_RCVR_TIMEOUT;
|
||||||
|
}
|
||||||
|
|
||||||
/* Register uavobj callback */
|
/* Register uavobj callback */
|
||||||
GCSReceiverConnectCallback (gcsreceiver_updated);
|
GCSReceiverConnectCallback (gcsreceiver_updated);
|
||||||
|
|
||||||
@ -133,11 +138,18 @@ extern int32_t PIOS_GCSRCVR_Init(uint32_t *gcsrcvr_id)
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get the value of an input channel
|
||||||
|
* \param[in] channel Number of the channel desired (zero based)
|
||||||
|
* \output PIOS_RCVR_INVALID channel not available
|
||||||
|
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||||
|
* \output >=0 channel value
|
||||||
|
*/
|
||||||
static int32_t PIOS_GCSRCVR_Get(uint32_t rcvr_id, uint8_t channel)
|
static int32_t PIOS_GCSRCVR_Get(uint32_t rcvr_id, uint8_t channel)
|
||||||
{
|
{
|
||||||
if (channel >= GCSRECEIVER_CHANNEL_NUMELEM) {
|
if (channel >= GCSRECEIVER_CHANNEL_NUMELEM) {
|
||||||
/* channel is out of range */
|
/* channel is out of range */
|
||||||
return -1;
|
return PIOS_RCVR_INVALID;
|
||||||
}
|
}
|
||||||
|
|
||||||
return (gcsreceiverdata.Channel[channel]);
|
return (gcsreceiverdata.Channel[channel]);
|
||||||
|
@ -166,7 +166,7 @@ out_fail:
|
|||||||
* \param[in] channel Number of the channel desired (zero based)
|
* \param[in] channel Number of the channel desired (zero based)
|
||||||
* \output PIOS_RCVR_INVALID channel not available
|
* \output PIOS_RCVR_INVALID channel not available
|
||||||
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||||
* \output >0 channel value
|
* \output >=0 channel value
|
||||||
*/
|
*/
|
||||||
static int32_t PIOS_SBus_Get(uint32_t rcvr_id, uint8_t channel)
|
static int32_t PIOS_SBus_Get(uint32_t rcvr_id, uint8_t channel)
|
||||||
{
|
{
|
||||||
|
@ -18,7 +18,7 @@ ARCHFLAGS += -mcpu=cortex-m3 --specs=nano.specs
|
|||||||
ASRC += $(PIOS_DEVLIB)startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S
|
ASRC += $(PIOS_DEVLIB)startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S
|
||||||
|
|
||||||
# PIOS device library source and includes
|
# PIOS device library source and includes
|
||||||
SRC += $(wildcard $(PIOS_DEVLIB)*.c)
|
SRC += $(sort $(wildcard $(PIOS_DEVLIB)*.c))
|
||||||
|
|
||||||
# CMSIS for the F1
|
# CMSIS for the F1
|
||||||
include $(PIOS)/Common/Libraries/CMSIS2/library.mk
|
include $(PIOS)/Common/Libraries/CMSIS2/library.mk
|
||||||
@ -29,12 +29,12 @@ EXTRAINCDIRS += $(CMSIS_DIR)
|
|||||||
|
|
||||||
# ST Peripheral library
|
# ST Peripheral library
|
||||||
PERIPHLIB = $(PIOS_DEVLIB)Libraries/STM32F10x_StdPeriph_Driver
|
PERIPHLIB = $(PIOS_DEVLIB)Libraries/STM32F10x_StdPeriph_Driver
|
||||||
SRC += $(wildcard $(PERIPHLIB)/src/*.c)
|
SRC += $(sort $(wildcard $(PERIPHLIB)/src/*.c))
|
||||||
EXTRAINCDIRS += $(PERIPHLIB)/inc
|
EXTRAINCDIRS += $(PERIPHLIB)/inc
|
||||||
|
|
||||||
# ST USB Device library
|
# ST USB Device library
|
||||||
USBDEVLIB = $(PIOS_DEVLIB)Libraries/STM32_USB-FS-Device_Driver
|
USBDEVLIB = $(PIOS_DEVLIB)Libraries/STM32_USB-FS-Device_Driver
|
||||||
SRC += $(wildcard $(USBDEVLIB)/src/*.c)
|
SRC += $(sort $(wildcard $(USBDEVLIB)/src/*.c))
|
||||||
EXTRAINCDIRS += $(USBDEVLIB)/inc
|
EXTRAINCDIRS += $(USBDEVLIB)/inc
|
||||||
|
|
||||||
#
|
#
|
||||||
@ -45,7 +45,7 @@ EXTRAINCDIRS += $(USBDEVLIB)/inc
|
|||||||
#
|
#
|
||||||
ifneq ($(FREERTOS_DIR),)
|
ifneq ($(FREERTOS_DIR),)
|
||||||
FREERTOS_PORTDIR := $(PIOS_DEVLIB)Libraries/FreeRTOS/Source
|
FREERTOS_PORTDIR := $(PIOS_DEVLIB)Libraries/FreeRTOS/Source
|
||||||
SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM3/*.c)
|
SRC += $(sort $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM3/*.c))
|
||||||
SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/MemMang/heap_1.c)
|
SRC += $(sort $(wildcard $(FREERTOS_PORTDIR)/portable/MemMang/heap_1.c))
|
||||||
EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM3
|
EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM3
|
||||||
endif
|
endif
|
||||||
|
@ -348,7 +348,7 @@ static uint16_t PIOS_DSM_RxInCallback(uint32_t context,
|
|||||||
* \param[in] channel Number of the channel desired (zero based)
|
* \param[in] channel Number of the channel desired (zero based)
|
||||||
* \output PIOS_RCVR_INVALID channel not available
|
* \output PIOS_RCVR_INVALID channel not available
|
||||||
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||||
* \output >0 channel value
|
* \output >=0 channel value
|
||||||
*/
|
*/
|
||||||
static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel)
|
static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||||
{
|
{
|
||||||
|
@ -146,8 +146,8 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg)
|
|||||||
|
|
||||||
for (uint8_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
|
for (uint8_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
|
||||||
/* Flush counter variables */
|
/* Flush counter variables */
|
||||||
ppm_dev->CaptureValue[i] = 0;
|
ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT;
|
||||||
ppm_dev->CaptureValueNewFrame[i] = 0;
|
ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -201,11 +201,12 @@ out_fail:
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Get the value of an input channel
|
* Get the value of an input channel
|
||||||
* \param[in] Channel Number of the channel desired
|
* \param[in] channel Number of the channel desired (zero based)
|
||||||
* \output -1 Channel not available
|
* \output PIOS_RCVR_INVALID channel not available
|
||||||
* \output >0 Channel value
|
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||||
*/
|
* \output >=0 channel value
|
||||||
|
*/
|
||||||
static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel)
|
static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||||
{
|
{
|
||||||
struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)rcvr_id;
|
struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)rcvr_id;
|
||||||
|
@ -171,11 +171,12 @@ out_fail:
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Get the value of an input channel
|
* Get the value of an input channel
|
||||||
* \param[in] Channel Number of the channel desired
|
* \param[in] channel Number of the channel desired (zero based)
|
||||||
* \output -1 Channel not available
|
* \output PIOS_RCVR_INVALID channel not available
|
||||||
* \output >0 Channel value
|
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||||
*/
|
* \output >=0 channel value
|
||||||
|
*/
|
||||||
static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel)
|
static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||||
{
|
{
|
||||||
struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)rcvr_id;
|
struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)rcvr_id;
|
||||||
|
@ -20,18 +20,18 @@ CDEFS += -DARM_MATH_CM4 -D__FPU_PRESENT=1
|
|||||||
ARCHFLAGS += -mcpu=cortex-m4 -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
|
ARCHFLAGS += -mcpu=cortex-m4 -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
|
||||||
|
|
||||||
# PIOS device library source and includes
|
# PIOS device library source and includes
|
||||||
SRC += $(wildcard $(PIOS_DEVLIB)*.c)
|
SRC += $(sort $(wildcard $(PIOS_DEVLIB)*.c))
|
||||||
EXTRAINCDIRS += $(PIOS_DEVLIB)inc
|
EXTRAINCDIRS += $(PIOS_DEVLIB)inc
|
||||||
|
|
||||||
# CMSIS for the F4
|
# CMSIS for the F4
|
||||||
include $(PIOSCOMMON)/Libraries/CMSIS2/library.mk
|
include $(PIOSCOMMON)/Libraries/CMSIS2/library.mk
|
||||||
CMSIS2_DEVICEDIR := $(PIOS_DEVLIB)Libraries/CMSIS2/Device/ST/STM32F4xx
|
CMSIS2_DEVICEDIR := $(PIOS_DEVLIB)Libraries/CMSIS2/Device/ST/STM32F4xx
|
||||||
SRC += $(wildcard $(CMSIS2_DEVICEDIR)/Source/$(BOARD_NAME)/*.c)
|
SRC += $(sort $(wildcard $(CMSIS2_DEVICEDIR)/Source/$(BOARD_NAME)/*.c))
|
||||||
EXTRAINCDIRS += $(CMSIS2_DEVICEDIR)/Include
|
EXTRAINCDIRS += $(CMSIS2_DEVICEDIR)/Include
|
||||||
|
|
||||||
# ST Peripheral library
|
# ST Peripheral library
|
||||||
PERIPHLIB = $(PIOS_DEVLIB)Libraries/STM32F4xx_StdPeriph_Driver
|
PERIPHLIB = $(PIOS_DEVLIB)Libraries/STM32F4xx_StdPeriph_Driver
|
||||||
SRC += $(wildcard $(PERIPHLIB)/src/*.c)
|
SRC += $(sort $(wildcard $(PERIPHLIB)/src/*.c))
|
||||||
EXTRAINCDIRS += $(PERIPHLIB)/inc
|
EXTRAINCDIRS += $(PERIPHLIB)/inc
|
||||||
|
|
||||||
# ST USB OTG library
|
# ST USB OTG library
|
||||||
@ -42,7 +42,7 @@ EXTRAINCDIRS += $(USBOTGLIB)/inc
|
|||||||
|
|
||||||
# ST USB Device library
|
# ST USB Device library
|
||||||
USBDEVLIB = $(PIOS_DEVLIB)Libraries/STM32_USB_Device_Library
|
USBDEVLIB = $(PIOS_DEVLIB)Libraries/STM32_USB_Device_Library
|
||||||
SRC += $(wildcard $(USBDEVLIB)/Core/src/*.c)
|
SRC += $(sort $(wildcard $(USBDEVLIB)/Core/src/*.c))
|
||||||
EXTRAINCDIRS += $(USBDEVLIB)/Core/inc
|
EXTRAINCDIRS += $(USBDEVLIB)/Core/inc
|
||||||
|
|
||||||
#
|
#
|
||||||
@ -53,7 +53,7 @@ EXTRAINCDIRS += $(USBDEVLIB)/Core/inc
|
|||||||
#
|
#
|
||||||
ifneq ($(FREERTOS_DIR),)
|
ifneq ($(FREERTOS_DIR),)
|
||||||
FREERTOS_PORTDIR := $(PIOS_DEVLIB)Libraries/FreeRTOS/Source
|
FREERTOS_PORTDIR := $(PIOS_DEVLIB)Libraries/FreeRTOS/Source
|
||||||
SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4F/*.c)
|
SRC += $(sort $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4F/*.c))
|
||||||
EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4F
|
EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4F
|
||||||
include $(PIOSCOMMON)/Libraries/msheap/library.mk
|
include $(PIOSCOMMON)/Libraries/msheap/library.mk
|
||||||
endif
|
endif
|
||||||
|
@ -349,7 +349,7 @@ static uint16_t PIOS_DSM_RxInCallback(uint32_t context,
|
|||||||
* \param[in] channel Number of the channel desired (zero based)
|
* \param[in] channel Number of the channel desired (zero based)
|
||||||
* \output PIOS_RCVR_INVALID channel not available
|
* \output PIOS_RCVR_INVALID channel not available
|
||||||
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||||
* \output >0 channel value
|
* \output >=0 channel value
|
||||||
*/
|
*/
|
||||||
static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel)
|
static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||||
{
|
{
|
||||||
|
@ -145,8 +145,8 @@ extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg)
|
|||||||
|
|
||||||
for (uint8_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
|
for (uint8_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
|
||||||
/* Flush counter variables */
|
/* Flush counter variables */
|
||||||
ppm_dev->CaptureValue[i] = 0;
|
ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT;
|
||||||
ppm_dev->CaptureValueNewFrame[i] = 0;
|
ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -200,11 +200,12 @@ out_fail:
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Get the value of an input channel
|
* Get the value of an input channel
|
||||||
* \param[in] Channel Number of the channel desired
|
* \param[in] channel Number of the channel desired (zero based)
|
||||||
* \output -1 Channel not available
|
* \output PIOS_RCVR_INVALID channel not available
|
||||||
* \output >0 Channel value
|
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||||
*/
|
* \output >=0 channel value
|
||||||
|
*/
|
||||||
static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel)
|
static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||||
{
|
{
|
||||||
struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)rcvr_id;
|
struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)rcvr_id;
|
||||||
|
@ -170,11 +170,12 @@ out_fail:
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Get the value of an input channel
|
* Get the value of an input channel
|
||||||
* \param[in] Channel Number of the channel desired
|
* \param[in] channel Number of the channel desired (zero based)
|
||||||
* \output -1 Channel not available
|
* \output PIOS_RCVR_INVALID channel not available
|
||||||
* \output >0 Channel value
|
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||||
*/
|
* \output >=0 channel value
|
||||||
|
*/
|
||||||
static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel)
|
static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||||
{
|
{
|
||||||
struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)rcvr_id;
|
struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)rcvr_id;
|
||||||
|
@ -42,11 +42,11 @@ extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel);
|
|||||||
/*! Define error codes for PIOS_RCVR_Get */
|
/*! Define error codes for PIOS_RCVR_Get */
|
||||||
enum PIOS_RCVR_errors {
|
enum PIOS_RCVR_errors {
|
||||||
/*! Indicates that a failsafe condition or missing receiver detected for that channel */
|
/*! Indicates that a failsafe condition or missing receiver detected for that channel */
|
||||||
PIOS_RCVR_TIMEOUT = 0,
|
PIOS_RCVR_TIMEOUT = -1,
|
||||||
/*! Channel is invalid for this driver (usually out of range supported) */
|
/*! Channel is invalid for this driver (usually out of range supported) */
|
||||||
PIOS_RCVR_INVALID = -1,
|
PIOS_RCVR_INVALID = -2,
|
||||||
/*! Indicates that the driver for this channel has not been initialized */
|
/*! Indicates that the driver for this channel has not been initialized */
|
||||||
PIOS_RCVR_NODRIVER = -2
|
PIOS_RCVR_NODRIVER = -3
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* PIOS_RCVR_H */
|
#endif /* PIOS_RCVR_H */
|
||||||
|
@ -6,5 +6,5 @@
|
|||||||
#
|
#
|
||||||
|
|
||||||
FREERTOS_DIR := $(dir $(lastword $(MAKEFILE_LIST)))/Source
|
FREERTOS_DIR := $(dir $(lastword $(MAKEFILE_LIST)))/Source
|
||||||
SRC += $(wildcard $(FREERTOS_DIR)/*.c)
|
SRC += $(sort $(wildcard $(FREERTOS_DIR)/*.c))
|
||||||
EXTRAINCDIRS += $(FREERTOS_DIR)/include
|
EXTRAINCDIRS += $(FREERTOS_DIR)/include
|
||||||
|
@ -27,7 +27,7 @@ ARCHFLAGS += -DARCH_POSIX
|
|||||||
#
|
#
|
||||||
# PIOS device library source and includes
|
# PIOS device library source and includes
|
||||||
#
|
#
|
||||||
SRC += $(wildcard $(PIOS_DEVLIB)*.c)
|
SRC += $(sort $(wildcard $(PIOS_DEVLIB)*.c))
|
||||||
EXTRAINCDIRS += $(PIOS_DEVLIB)/inc
|
EXTRAINCDIRS += $(PIOS_DEVLIB)/inc
|
||||||
|
|
||||||
#
|
#
|
||||||
@ -68,8 +68,8 @@ EXTRAINCDIRS += $(PIOS_DEVLIB)/inc
|
|||||||
#
|
#
|
||||||
ifneq ($(FREERTOS_DIR),)
|
ifneq ($(FREERTOS_DIR),)
|
||||||
FREERTOS_PORTDIR := $(PIOS_DEVLIB)/Libraries/FreeRTOS/Source
|
FREERTOS_PORTDIR := $(PIOS_DEVLIB)/Libraries/FreeRTOS/Source
|
||||||
SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/Posix/*.c)
|
SRC += $(sort $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/Posix/*.c))
|
||||||
SRC += $(wildcard $(FREERTOS_PORTDIR)/portable/MemMang/*.c)
|
SRC += $(sort $(wildcard $(FREERTOS_PORTDIR)/portable/MemMang/*.c))
|
||||||
|
|
||||||
EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/Posix
|
EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/Posix
|
||||||
endif
|
endif
|
||||||
|
@ -62,7 +62,7 @@ ifndef TESTAPP
|
|||||||
SRC += $(OPSYSTEM)/coptercontrol.c
|
SRC += $(OPSYSTEM)/coptercontrol.c
|
||||||
SRC += $(OPSYSTEM)/pios_board.c
|
SRC += $(OPSYSTEM)/pios_board.c
|
||||||
SRC += $(OPSYSTEM)/pios_usb_board_data.c
|
SRC += $(OPSYSTEM)/pios_usb_board_data.c
|
||||||
SRC += $(OPSYSTEM)/alarms.c
|
SRC += $(FLIGHTLIB)/alarms.c
|
||||||
SRC += $(OPUAVTALK)/uavtalk.c
|
SRC += $(OPUAVTALK)/uavtalk.c
|
||||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||||
|
@ -1,50 +0,0 @@
|
|||||||
/**
|
|
||||||
******************************************************************************
|
|
||||||
* @addtogroup OpenPilotSystem OpenPilot System
|
|
||||||
* @{
|
|
||||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
|
||||||
* @{
|
|
||||||
* @file alarms.h
|
|
||||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
|
||||||
* @brief Include file of the alarm 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 ALARMS_H
|
|
||||||
#define ALARMS_H
|
|
||||||
|
|
||||||
#include "systemalarms.h"
|
|
||||||
#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED
|
|
||||||
|
|
||||||
int32_t AlarmsInitialize(void);
|
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity);
|
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm);
|
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm);
|
|
||||||
void AlarmsDefaultAll();
|
|
||||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm);
|
|
||||||
void AlarmsClearAll();
|
|
||||||
int32_t AlarmsHasWarnings();
|
|
||||||
int32_t AlarmsHasErrors();
|
|
||||||
int32_t AlarmsHasCritical();
|
|
||||||
|
|
||||||
#endif // ALARMS_H
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
@ -48,7 +48,7 @@ ifndef TESTAPP
|
|||||||
SRC += $(OPSYSTEM)/osd.c
|
SRC += $(OPSYSTEM)/osd.c
|
||||||
SRC += $(OPSYSTEM)/pios_board.c
|
SRC += $(OPSYSTEM)/pios_board.c
|
||||||
SRC += $(OPSYSTEM)/pios_usb_board_data.c
|
SRC += $(OPSYSTEM)/pios_usb_board_data.c
|
||||||
SRC += $(OPSYSTEM)/alarms.c
|
SRC += $(FLIGHTLIB)/alarms.c
|
||||||
SRC += $(OPUAVTALK)/uavtalk.c
|
SRC += $(OPUAVTALK)/uavtalk.c
|
||||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||||
|
@ -1,210 +0,0 @@
|
|||||||
/**
|
|
||||||
******************************************************************************
|
|
||||||
* @addtogroup OpenPilotSystem OpenPilot System
|
|
||||||
* @{
|
|
||||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
|
||||||
* @brief OpenPilot System libraries are available to all OP modules.
|
|
||||||
* @{
|
|
||||||
* @file alarms.c
|
|
||||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
|
||||||
* @brief Library for setting and clearing system alarms
|
|
||||||
* @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 "openpilot.h"
|
|
||||||
#include "alarms.h"
|
|
||||||
|
|
||||||
// Private constants
|
|
||||||
|
|
||||||
// Private types
|
|
||||||
|
|
||||||
// Private variables
|
|
||||||
static xSemaphoreHandle lock;
|
|
||||||
|
|
||||||
// Private functions
|
|
||||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Initialize the alarms library
|
|
||||||
*/
|
|
||||||
int32_t AlarmsInitialize(void)
|
|
||||||
{
|
|
||||||
SystemAlarmsInitialize();
|
|
||||||
lock = xSemaphoreCreateRecursiveMutex();
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set an alarm
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @param severity The alarm severity
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
|
||||||
{
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Lock
|
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
|
||||||
|
|
||||||
// Read alarm and update its severity only if it was changed
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
if ( alarms.Alarm[alarm] != severity )
|
|
||||||
{
|
|
||||||
alarms.Alarm[alarm] = severity;
|
|
||||||
SystemAlarmsSet(&alarms);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Release lock
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 0;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Get an alarm
|
|
||||||
* @param alarm The system alarm to be read
|
|
||||||
* @return Alarm severity
|
|
||||||
*/
|
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Read alarm
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
return alarms.Alarm[alarm];
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set an alarm to it's default value
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Default all alarms
|
|
||||||
*/
|
|
||||||
void AlarmsDefaultAll()
|
|
||||||
{
|
|
||||||
uint32_t n;
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
AlarmsDefault(n);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Clear an alarm
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Clear all alarms
|
|
||||||
*/
|
|
||||||
void AlarmsClearAll()
|
|
||||||
{
|
|
||||||
uint32_t n;
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
AlarmsClear(n);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with the given or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasWarnings()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_WARNING);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with error or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasErrors()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_ERROR);
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with critical or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasCritical()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL);
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with the given or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
uint32_t n;
|
|
||||||
|
|
||||||
// Lock
|
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
|
||||||
|
|
||||||
// Read alarms
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
|
|
||||||
// Go through alarms and check if any are of the given severity or higher
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
if ( alarms.Alarm[n] >= severity)
|
|
||||||
{
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// If this point is reached then no alarms found
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
||||||
|
|
@ -1,50 +0,0 @@
|
|||||||
/**
|
|
||||||
******************************************************************************
|
|
||||||
* @addtogroup OpenPilotSystem OpenPilot System
|
|
||||||
* @{
|
|
||||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
|
||||||
* @{
|
|
||||||
* @file alarms.h
|
|
||||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
|
||||||
* @brief Include file of the alarm 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 ALARMS_H
|
|
||||||
#define ALARMS_H
|
|
||||||
|
|
||||||
#include "systemalarms.h"
|
|
||||||
#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED
|
|
||||||
|
|
||||||
int32_t AlarmsInitialize(void);
|
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity);
|
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm);
|
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm);
|
|
||||||
void AlarmsDefaultAll();
|
|
||||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm);
|
|
||||||
void AlarmsClearAll();
|
|
||||||
int32_t AlarmsHasWarnings();
|
|
||||||
int32_t AlarmsHasErrors();
|
|
||||||
int32_t AlarmsHasCritical();
|
|
||||||
|
|
||||||
#endif // ALARMS_H
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
@ -1,214 +0,0 @@
|
|||||||
/**
|
|
||||||
******************************************************************************
|
|
||||||
* @addtogroup OpenPilotSystem OpenPilot System
|
|
||||||
* @{
|
|
||||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
|
||||||
* @brief OpenPilot System libraries are available to all OP modules.
|
|
||||||
* @{
|
|
||||||
* @file alarms.c
|
|
||||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
|
||||||
* @brief Library for setting and clearing system alarms
|
|
||||||
* @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 "openpilot.h"
|
|
||||||
#include "alarms.h"
|
|
||||||
|
|
||||||
// Private constants
|
|
||||||
|
|
||||||
// Private types
|
|
||||||
|
|
||||||
// Private variables
|
|
||||||
static xSemaphoreHandle lock;
|
|
||||||
|
|
||||||
// Private functions
|
|
||||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Initialize the alarms library
|
|
||||||
*/
|
|
||||||
int32_t AlarmsInitialize(void)
|
|
||||||
{
|
|
||||||
SystemAlarmsInitialize();
|
|
||||||
|
|
||||||
lock = xSemaphoreCreateRecursiveMutex();
|
|
||||||
//do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that
|
|
||||||
//AlarmsClearAll();
|
|
||||||
//AlarmsDefaultAll();
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set an alarm
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @param severity The alarm severity
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
|
||||||
{
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Lock
|
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
|
||||||
|
|
||||||
// Read alarm and update its severity only if it was changed
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
if ( alarms.Alarm[alarm] != severity )
|
|
||||||
{
|
|
||||||
alarms.Alarm[alarm] = severity;
|
|
||||||
SystemAlarmsSet(&alarms);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Release lock
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 0;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Get an alarm
|
|
||||||
* @param alarm The system alarm to be read
|
|
||||||
* @return Alarm severity
|
|
||||||
*/
|
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Read alarm
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
return alarms.Alarm[alarm];
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set an alarm to it's default value
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Default all alarms
|
|
||||||
*/
|
|
||||||
void AlarmsDefaultAll()
|
|
||||||
{
|
|
||||||
uint32_t n;
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
AlarmsDefault(n);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Clear an alarm
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Clear all alarms
|
|
||||||
*/
|
|
||||||
void AlarmsClearAll()
|
|
||||||
{
|
|
||||||
uint32_t n;
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
AlarmsClear(n);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with the given or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasWarnings()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_WARNING);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with error or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasErrors()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_ERROR);
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with critical or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasCritical()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL);
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with the given or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
uint32_t n;
|
|
||||||
|
|
||||||
// Lock
|
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
|
||||||
|
|
||||||
// Read alarms
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
|
|
||||||
// Go through alarms and check if any are of the given severity or higher
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
if ( alarms.Alarm[n] >= severity)
|
|
||||||
{
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// If this point is reached then no alarms found
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
||||||
|
|
@ -66,7 +66,7 @@ ifndef TESTAPP
|
|||||||
SRC += $(OPSYSTEM)/revolution.c
|
SRC += $(OPSYSTEM)/revolution.c
|
||||||
SRC += $(OPSYSTEM)/pios_board.c
|
SRC += $(OPSYSTEM)/pios_board.c
|
||||||
SRC += $(OPSYSTEM)/pios_usb_board_data.c
|
SRC += $(OPSYSTEM)/pios_usb_board_data.c
|
||||||
SRC += $(OPSYSTEM)/alarms.c
|
SRC += $(FLIGHTLIB)/alarms.c
|
||||||
SRC += $(OPUAVTALK)/uavtalk.c
|
SRC += $(OPUAVTALK)/uavtalk.c
|
||||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||||
|
@ -1,210 +0,0 @@
|
|||||||
/**
|
|
||||||
******************************************************************************
|
|
||||||
* @addtogroup OpenPilotSystem OpenPilot System
|
|
||||||
* @{
|
|
||||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
|
||||||
* @brief OpenPilot System libraries are available to all OP modules.
|
|
||||||
* @{
|
|
||||||
* @file alarms.c
|
|
||||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
|
||||||
* @brief Library for setting and clearing system alarms
|
|
||||||
* @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 "openpilot.h"
|
|
||||||
#include "alarms.h"
|
|
||||||
|
|
||||||
// Private constants
|
|
||||||
|
|
||||||
// Private types
|
|
||||||
|
|
||||||
// Private variables
|
|
||||||
static xSemaphoreHandle lock;
|
|
||||||
|
|
||||||
// Private functions
|
|
||||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Initialize the alarms library
|
|
||||||
*/
|
|
||||||
int32_t AlarmsInitialize(void)
|
|
||||||
{
|
|
||||||
SystemAlarmsInitialize();
|
|
||||||
lock = xSemaphoreCreateRecursiveMutex();
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set an alarm
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @param severity The alarm severity
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
|
||||||
{
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Lock
|
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
|
||||||
|
|
||||||
// Read alarm and update its severity only if it was changed
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
if ( alarms.Alarm[alarm] != severity )
|
|
||||||
{
|
|
||||||
alarms.Alarm[alarm] = severity;
|
|
||||||
SystemAlarmsSet(&alarms);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Release lock
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 0;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Get an alarm
|
|
||||||
* @param alarm The system alarm to be read
|
|
||||||
* @return Alarm severity
|
|
||||||
*/
|
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Read alarm
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
return alarms.Alarm[alarm];
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set an alarm to it's default value
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Default all alarms
|
|
||||||
*/
|
|
||||||
void AlarmsDefaultAll()
|
|
||||||
{
|
|
||||||
uint32_t n;
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
AlarmsDefault(n);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Clear an alarm
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Clear all alarms
|
|
||||||
*/
|
|
||||||
void AlarmsClearAll()
|
|
||||||
{
|
|
||||||
uint32_t n;
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
AlarmsClear(n);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with the given or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasWarnings()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_WARNING);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with error or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasErrors()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_ERROR);
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with critical or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasCritical()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL);
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with the given or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
uint32_t n;
|
|
||||||
|
|
||||||
// Lock
|
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
|
||||||
|
|
||||||
// Read alarms
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
|
|
||||||
// Go through alarms and check if any are of the given severity or higher
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
if ( alarms.Alarm[n] >= severity)
|
|
||||||
{
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// If this point is reached then no alarms found
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
||||||
|
|
@ -1,50 +0,0 @@
|
|||||||
/**
|
|
||||||
******************************************************************************
|
|
||||||
* @addtogroup OpenPilotSystem OpenPilot System
|
|
||||||
* @{
|
|
||||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
|
||||||
* @{
|
|
||||||
* @file alarms.h
|
|
||||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
|
||||||
* @brief Include file of the alarm 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 ALARMS_H
|
|
||||||
#define ALARMS_H
|
|
||||||
|
|
||||||
#include "systemalarms.h"
|
|
||||||
#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED
|
|
||||||
|
|
||||||
int32_t AlarmsInitialize(void);
|
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity);
|
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm);
|
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm);
|
|
||||||
void AlarmsDefaultAll();
|
|
||||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm);
|
|
||||||
void AlarmsClearAll();
|
|
||||||
int32_t AlarmsHasWarnings();
|
|
||||||
int32_t AlarmsHasErrors();
|
|
||||||
int32_t AlarmsHasCritical();
|
|
||||||
|
|
||||||
#endif // ALARMS_H
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
@ -66,7 +66,7 @@ ifndef TESTAPP
|
|||||||
SRC += $(OPSYSTEM)/revolution.c
|
SRC += $(OPSYSTEM)/revolution.c
|
||||||
SRC += $(OPSYSTEM)/pios_board.c
|
SRC += $(OPSYSTEM)/pios_board.c
|
||||||
SRC += $(OPSYSTEM)/pios_usb_board_data.c
|
SRC += $(OPSYSTEM)/pios_usb_board_data.c
|
||||||
SRC += $(OPSYSTEM)/alarms.c
|
SRC += $(FLIGHTLIB)/alarms.c
|
||||||
SRC += $(OPUAVTALK)/uavtalk.c
|
SRC += $(OPUAVTALK)/uavtalk.c
|
||||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||||
|
@ -1,210 +0,0 @@
|
|||||||
/**
|
|
||||||
******************************************************************************
|
|
||||||
* @addtogroup OpenPilotSystem OpenPilot System
|
|
||||||
* @{
|
|
||||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
|
||||||
* @brief OpenPilot System libraries are available to all OP modules.
|
|
||||||
* @{
|
|
||||||
* @file alarms.c
|
|
||||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
|
||||||
* @brief Library for setting and clearing system alarms
|
|
||||||
* @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 "openpilot.h"
|
|
||||||
#include "alarms.h"
|
|
||||||
|
|
||||||
// Private constants
|
|
||||||
|
|
||||||
// Private types
|
|
||||||
|
|
||||||
// Private variables
|
|
||||||
static xSemaphoreHandle lock;
|
|
||||||
|
|
||||||
// Private functions
|
|
||||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Initialize the alarms library
|
|
||||||
*/
|
|
||||||
int32_t AlarmsInitialize(void)
|
|
||||||
{
|
|
||||||
SystemAlarmsInitialize();
|
|
||||||
lock = xSemaphoreCreateRecursiveMutex();
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set an alarm
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @param severity The alarm severity
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
|
||||||
{
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Lock
|
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
|
||||||
|
|
||||||
// Read alarm and update its severity only if it was changed
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
if ( alarms.Alarm[alarm] != severity )
|
|
||||||
{
|
|
||||||
alarms.Alarm[alarm] = severity;
|
|
||||||
SystemAlarmsSet(&alarms);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Release lock
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 0;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Get an alarm
|
|
||||||
* @param alarm The system alarm to be read
|
|
||||||
* @return Alarm severity
|
|
||||||
*/
|
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Read alarm
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
return alarms.Alarm[alarm];
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set an alarm to it's default value
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Default all alarms
|
|
||||||
*/
|
|
||||||
void AlarmsDefaultAll()
|
|
||||||
{
|
|
||||||
uint32_t n;
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
AlarmsDefault(n);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Clear an alarm
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Clear all alarms
|
|
||||||
*/
|
|
||||||
void AlarmsClearAll()
|
|
||||||
{
|
|
||||||
uint32_t n;
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
AlarmsClear(n);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with the given or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasWarnings()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_WARNING);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with error or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasErrors()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_ERROR);
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with critical or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasCritical()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL);
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with the given or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
uint32_t n;
|
|
||||||
|
|
||||||
// Lock
|
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
|
||||||
|
|
||||||
// Read alarms
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
|
|
||||||
// Go through alarms and check if any are of the given severity or higher
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
if ( alarms.Alarm[n] >= severity)
|
|
||||||
{
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// If this point is reached then no alarms found
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
||||||
|
|
@ -1,50 +0,0 @@
|
|||||||
/**
|
|
||||||
******************************************************************************
|
|
||||||
* @addtogroup OpenPilotSystem OpenPilot System
|
|
||||||
* @{
|
|
||||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
|
||||||
* @{
|
|
||||||
* @file alarms.h
|
|
||||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
|
||||||
* @brief Include file of the alarm 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 ALARMS_H
|
|
||||||
#define ALARMS_H
|
|
||||||
|
|
||||||
#include "systemalarms.h"
|
|
||||||
#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED
|
|
||||||
|
|
||||||
int32_t AlarmsInitialize(void);
|
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity);
|
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm);
|
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm);
|
|
||||||
void AlarmsDefaultAll();
|
|
||||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm);
|
|
||||||
void AlarmsClearAll();
|
|
||||||
int32_t AlarmsHasWarnings();
|
|
||||||
int32_t AlarmsHasErrors();
|
|
||||||
int32_t AlarmsHasCritical();
|
|
||||||
|
|
||||||
#endif // ALARMS_H
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
@ -78,7 +78,7 @@ SRC += ${OUTDIR}/InitMods.c
|
|||||||
SRC += ${OPMODULEDIR}/System/systemmod.c
|
SRC += ${OPMODULEDIR}/System/systemmod.c
|
||||||
SRC += $(OPSYSTEM)/simposix.c
|
SRC += $(OPSYSTEM)/simposix.c
|
||||||
SRC += $(OPSYSTEM)/pios_board.c
|
SRC += $(OPSYSTEM)/pios_board.c
|
||||||
SRC += $(OPSYSTEM)/alarms.c
|
SRC += $(FLIGHTLIB)/alarms.c
|
||||||
SRC += $(OPUAVTALK)/uavtalk.c
|
SRC += $(OPUAVTALK)/uavtalk.c
|
||||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||||
|
@ -1,210 +0,0 @@
|
|||||||
/**
|
|
||||||
******************************************************************************
|
|
||||||
* @addtogroup OpenPilotSystem OpenPilot System
|
|
||||||
* @{
|
|
||||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
|
||||||
* @brief OpenPilot System libraries are available to all OP modules.
|
|
||||||
* @{
|
|
||||||
* @file alarms.c
|
|
||||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
|
||||||
* @brief Library for setting and clearing system alarms
|
|
||||||
* @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 "openpilot.h"
|
|
||||||
#include "alarms.h"
|
|
||||||
|
|
||||||
// Private constants
|
|
||||||
|
|
||||||
// Private types
|
|
||||||
|
|
||||||
// Private variables
|
|
||||||
static xSemaphoreHandle lock;
|
|
||||||
|
|
||||||
// Private functions
|
|
||||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Initialize the alarms library
|
|
||||||
*/
|
|
||||||
int32_t AlarmsInitialize(void)
|
|
||||||
{
|
|
||||||
SystemAlarmsInitialize();
|
|
||||||
lock = xSemaphoreCreateRecursiveMutex();
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set an alarm
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @param severity The alarm severity
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
|
||||||
{
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Lock
|
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
|
||||||
|
|
||||||
// Read alarm and update its severity only if it was changed
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
if ( alarms.Alarm[alarm] != severity )
|
|
||||||
{
|
|
||||||
alarms.Alarm[alarm] = severity;
|
|
||||||
SystemAlarmsSet(&alarms);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Release lock
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 0;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Get an alarm
|
|
||||||
* @param alarm The system alarm to be read
|
|
||||||
* @return Alarm severity
|
|
||||||
*/
|
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
|
|
||||||
// Check that this is a valid alarm
|
|
||||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Read alarm
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
return alarms.Alarm[alarm];
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set an alarm to it's default value
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Default all alarms
|
|
||||||
*/
|
|
||||||
void AlarmsDefaultAll()
|
|
||||||
{
|
|
||||||
uint32_t n;
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
AlarmsDefault(n);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Clear an alarm
|
|
||||||
* @param alarm The system alarm to be modified
|
|
||||||
* @return 0 if success, -1 if an error
|
|
||||||
*/
|
|
||||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm)
|
|
||||||
{
|
|
||||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Clear all alarms
|
|
||||||
*/
|
|
||||||
void AlarmsClearAll()
|
|
||||||
{
|
|
||||||
uint32_t n;
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
AlarmsClear(n);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with the given or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasWarnings()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_WARNING);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with error or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasErrors()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_ERROR);
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with critical or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
int32_t AlarmsHasCritical()
|
|
||||||
{
|
|
||||||
return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL);
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Check if there are any alarms with the given or higher severity
|
|
||||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
|
||||||
*/
|
|
||||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
|
||||||
{
|
|
||||||
SystemAlarmsData alarms;
|
|
||||||
uint32_t n;
|
|
||||||
|
|
||||||
// Lock
|
|
||||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
|
||||||
|
|
||||||
// Read alarms
|
|
||||||
SystemAlarmsGet(&alarms);
|
|
||||||
|
|
||||||
// Go through alarms and check if any are of the given severity or higher
|
|
||||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
|
||||||
{
|
|
||||||
if ( alarms.Alarm[n] >= severity)
|
|
||||||
{
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// If this point is reached then no alarms found
|
|
||||||
xSemaphoreGiveRecursive(lock);
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
||||||
|
|
@ -1,50 +0,0 @@
|
|||||||
/**
|
|
||||||
******************************************************************************
|
|
||||||
* @addtogroup OpenPilotSystem OpenPilot System
|
|
||||||
* @{
|
|
||||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
|
||||||
* @{
|
|
||||||
* @file alarms.h
|
|
||||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
|
||||||
* @brief Include file of the alarm 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 ALARMS_H
|
|
||||||
#define ALARMS_H
|
|
||||||
|
|
||||||
#include "systemalarms.h"
|
|
||||||
#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED
|
|
||||||
|
|
||||||
int32_t AlarmsInitialize(void);
|
|
||||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity);
|
|
||||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm);
|
|
||||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm);
|
|
||||||
void AlarmsDefaultAll();
|
|
||||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm);
|
|
||||||
void AlarmsClearAll();
|
|
||||||
int32_t AlarmsHasWarnings();
|
|
||||||
int32_t AlarmsHasErrors();
|
|
||||||
int32_t AlarmsHasCritical();
|
|
||||||
|
|
||||||
#endif // ALARMS_H
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
@ -17,16 +17,17 @@ PYTHON_DIR = python-2.7.4
|
|||||||
# Search the python using environment override first
|
# Search the python using environment override first
|
||||||
OPENPILOT_TOOLS_DIR = $$(OPENPILOT_TOOLS_DIR)
|
OPENPILOT_TOOLS_DIR = $$(OPENPILOT_TOOLS_DIR)
|
||||||
!isEmpty(OPENPILOT_TOOLS_DIR):exists($$OPENPILOT_TOOLS_DIR/$$PYTHON_DIR/python*) {
|
!isEmpty(OPENPILOT_TOOLS_DIR):exists($$OPENPILOT_TOOLS_DIR/$$PYTHON_DIR/python*) {
|
||||||
PYTHON = $$OPENPILOT_TOOLS_DIR/$$PYTHON_DIR/python
|
PYTHON = \"$$OPENPILOT_TOOLS_DIR/$$PYTHON_DIR/python\"
|
||||||
} else {
|
} else {
|
||||||
# If not found, search the predefined tools path
|
# If not found, search the predefined tools path
|
||||||
exists($$ROOT_DIR/tools/$$PYTHON_DIR/python*) {
|
exists($$ROOT_DIR/tools/$$PYTHON_DIR/python*) {
|
||||||
PYTHON = $$ROOT_DIR/tools/$$PYTHON_DIR/python
|
PYTHON = \"$$ROOT_DIR/tools/$$PYTHON_DIR/python\"
|
||||||
} else {
|
} else {
|
||||||
# not found, hope it's in the path...
|
# not found, hope it's in the path...
|
||||||
PYTHON = python
|
PYTHON = \"python\"
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
PYTHON = $$replace(PYTHON, \\\\, /)
|
||||||
message(Using python interpreter: $$PYTHON)
|
message(Using python interpreter: $$PYTHON)
|
||||||
|
|
||||||
# Define other variables
|
# Define other variables
|
||||||
|
@ -26,6 +26,57 @@
|
|||||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
The GCS locale is set to the system locale by default unless the "hidden" setting General/Locale has a value.
|
||||||
|
The user can not change General/Locale from the Options dialog.
|
||||||
|
|
||||||
|
The GCS language will default to the GCS locale unless the General/OverrideLanguage has a value.
|
||||||
|
The user can change General/OverrideLanguage to any available language from the Options dialog.
|
||||||
|
|
||||||
|
Both General/Locale and General/OverrideLanguage can be set from the command line or through the the factory defaults file.
|
||||||
|
|
||||||
|
The -D option is used to permanently set a user setting.
|
||||||
|
|
||||||
|
The -reset switch will clear all the user settings and will trigger a reload of the factory defaults.
|
||||||
|
|
||||||
|
You can combine it with the -config-file=<file> command line argument to quickly switch between multiple settings files.
|
||||||
|
|
||||||
|
[code]
|
||||||
|
openpilotgcs -reset -config-file ./MyOpenPilotGCS.xml
|
||||||
|
[/code]
|
||||||
|
|
||||||
|
Relative paths are relative to <install dir>/share/openpilotgcs/default_configurations/
|
||||||
|
|
||||||
|
The specified file will be used to load the factory defaults from but only when the user settings are empty.
|
||||||
|
If the user settings are not empty the file will not be used.
|
||||||
|
This switch is useful on the 1st run when the user settings are empty or in combination with -reset.
|
||||||
|
|
||||||
|
|
||||||
|
Quickly switch configurations
|
||||||
|
|
||||||
|
[code]
|
||||||
|
openpilotgcs -reset -config-file <relative or absolute path>
|
||||||
|
[/code]
|
||||||
|
|
||||||
|
Configuring GCS from installer
|
||||||
|
|
||||||
|
The -D option is used to permanently set a user setting.
|
||||||
|
|
||||||
|
If the user chooses to start GCS at the end of the installer:
|
||||||
|
|
||||||
|
[code]
|
||||||
|
openpilotgcs -D General/OverrideLanguage=de
|
||||||
|
[/code]
|
||||||
|
|
||||||
|
If the user chooses not to start GCS at the end of the installer, you still need to configure GCS.
|
||||||
|
In that case you can use -exit-after-config
|
||||||
|
|
||||||
|
[code]
|
||||||
|
openpilotgcs -D General/OverrideLanguage=de -exit-after-config
|
||||||
|
[/code]
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
#include "qtsingleapplication.h"
|
#include "qtsingleapplication.h"
|
||||||
#include "utils/xmlconfig.h"
|
#include "utils/xmlconfig.h"
|
||||||
#include "gcssplashscreen.h"
|
#include "gcssplashscreen.h"
|
||||||
@ -35,6 +86,7 @@
|
|||||||
#include <extensionsystem/iplugin.h>
|
#include <extensionsystem/iplugin.h>
|
||||||
|
|
||||||
#include <QtCore/QDir>
|
#include <QtCore/QDir>
|
||||||
|
#include <QtCore/QElapsedTimer>
|
||||||
#include <QtCore/QTextStream>
|
#include <QtCore/QTextStream>
|
||||||
#include <QtCore/QFileInfo>
|
#include <QtCore/QFileInfo>
|
||||||
#include <QtCore/QDebug>
|
#include <QtCore/QDebug>
|
||||||
@ -48,292 +100,415 @@
|
|||||||
#include <QtGui/QApplication>
|
#include <QtGui/QApplication>
|
||||||
#include <QtGui/QMainWindow>
|
#include <QtGui/QMainWindow>
|
||||||
#include <QtGui/QSplashScreen>
|
#include <QtGui/QSplashScreen>
|
||||||
#include <QtGui/QPainter>
|
|
||||||
|
|
||||||
#include <QElapsedTimer>
|
namespace {
|
||||||
|
|
||||||
enum { OptionIndent = 4, DescriptionIndent = 24 };
|
typedef QList<ExtensionSystem::PluginSpec *> PluginSpecSet;
|
||||||
|
typedef QMap<QString, bool> AppOptions;
|
||||||
|
typedef QMap<QString, QString> AppOptionValues;
|
||||||
|
|
||||||
static const char *appNameC = "OpenPilot GCS";
|
const int OptionIndent = 4;
|
||||||
static const char *corePluginNameC = "Core";
|
const int DescriptionIndent = 24;
|
||||||
static const char *fixedOptionsC =
|
|
||||||
" [OPTION]... [FILE]...\n"
|
|
||||||
"Options:\n"
|
|
||||||
" -help Display this help\n"
|
|
||||||
" -version Display program version\n"
|
|
||||||
" -client Attempt to connect to already running instance\n"
|
|
||||||
" -clean-config Delete all existing configuration settings\n"
|
|
||||||
" -exit-after-config Exit GCS after manipulating configuration settings\n"
|
|
||||||
" -D key=value Override configuration settings e.g: -D General/OverrideLanguage=de\n"
|
|
||||||
" -configfile=value Default configuration file to load if settings file is empty\n";
|
|
||||||
static const char *HELP_OPTION1 = "-h";
|
|
||||||
static const char *HELP_OPTION2 = "-help";
|
|
||||||
static const char *HELP_OPTION3 = "/h";
|
|
||||||
static const char *HELP_OPTION4 = "--help";
|
|
||||||
static const char *VERSION_OPTION = "-version";
|
|
||||||
static const char *CLIENT_OPTION = "-client";
|
|
||||||
static const char *CONFIG_OPTION = "-D";
|
|
||||||
static const char *CLEAN_CONFIG_OPTION = "-clean-config";
|
|
||||||
static const char *EXIT_AFTER_CONFIG_OPTION = "-exit-after-config";
|
|
||||||
|
|
||||||
typedef QList<ExtensionSystem::PluginSpec *> PluginSpecSet;
|
const QLatin1String APP_NAME("OpenPilot GCS");
|
||||||
|
|
||||||
// Helpers for displaying messages. Note that there is no console on Windows.
|
const QLatin1String CORE_PLUGIN_NAME("Core");
|
||||||
#ifdef Q_OS_WIN
|
|
||||||
// Format as <pre> HTML
|
|
||||||
static inline void toHtml(QString &t)
|
|
||||||
{
|
|
||||||
t.replace(QLatin1Char('&'), QLatin1String("&"));
|
|
||||||
t.replace(QLatin1Char('<'), QLatin1String("<"));
|
|
||||||
t.replace(QLatin1Char('>'), QLatin1String(">"));
|
|
||||||
t.insert(0, QLatin1String("<html><pre>"));
|
|
||||||
t.append(QLatin1String("</pre></html>"));
|
|
||||||
}
|
|
||||||
|
|
||||||
static void displayHelpText(QString t) // No console on Windows.
|
const QLatin1String SETTINGS_ORG_NAME("OpenPilot");
|
||||||
{
|
const QLatin1String SETTINGS_APP_NAME("OpenPilotGCS_config");
|
||||||
toHtml(t);
|
|
||||||
QMessageBox::information(0, QLatin1String(appNameC), t);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void displayError(const QString &t) // No console on Windows.
|
|
||||||
{
|
|
||||||
QMessageBox::critical(0, QLatin1String(appNameC), t);
|
|
||||||
}
|
|
||||||
|
|
||||||
#else
|
|
||||||
|
|
||||||
static void displayHelpText(const QString &t)
|
|
||||||
{
|
|
||||||
qWarning("%s", qPrintable(t));
|
|
||||||
}
|
|
||||||
|
|
||||||
static void displayError(const QString &t)
|
|
||||||
{
|
|
||||||
qCritical("%s", qPrintable(t));
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static void printVersion(const ExtensionSystem::PluginSpec *coreplugin,
|
|
||||||
const ExtensionSystem::PluginManager &pm)
|
|
||||||
{
|
|
||||||
QString version;
|
|
||||||
QTextStream str(&version);
|
|
||||||
str << '\n' << appNameC << ' ' << coreplugin->version()<< " based on Qt " << qVersion() << "\n\n";
|
|
||||||
pm.formatPluginVersions(str);
|
|
||||||
str << '\n' << coreplugin->copyright() << '\n';
|
|
||||||
displayHelpText(version);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void printHelp(const QString &a0, const ExtensionSystem::PluginManager &pm)
|
|
||||||
{
|
|
||||||
QString help;
|
|
||||||
QTextStream str(&help);
|
|
||||||
str << "Usage: " << a0 << fixedOptionsC;
|
|
||||||
ExtensionSystem::PluginManager::formatOptions(str, OptionIndent, DescriptionIndent);
|
|
||||||
pm.formatPluginOptions(str, OptionIndent, DescriptionIndent);
|
|
||||||
displayHelpText(help);
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline QString msgCoreLoadFailure(const QString &why)
|
|
||||||
{
|
|
||||||
return QCoreApplication::translate("Application", "Failed to load core: %1").arg(why);
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline QString msgSendArgumentFailed()
|
|
||||||
{
|
|
||||||
return QCoreApplication::translate("Application", "Unable to send command line arguments to the already running instance. It appears to be not responding.");
|
|
||||||
}
|
|
||||||
|
|
||||||
// Prepare a remote argument: If it is a relative file, add the current directory
|
|
||||||
// since the the central instance might be running in a different directory.
|
|
||||||
|
|
||||||
static inline QString prepareRemoteArgument(const QString &a)
|
|
||||||
{
|
|
||||||
QFileInfo fi(a);
|
|
||||||
if (!fi.exists())
|
|
||||||
return a;
|
|
||||||
if (fi.isRelative())
|
|
||||||
return fi.absoluteFilePath();
|
|
||||||
return a;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Send the arguments to an already running instance of OpenPilot GCS
|
|
||||||
static bool sendArguments(SharedTools::QtSingleApplication &app, const QStringList &arguments)
|
|
||||||
{
|
|
||||||
if (!arguments.empty()) {
|
|
||||||
// Send off arguments
|
|
||||||
const QStringList::const_iterator acend = arguments.constEnd();
|
|
||||||
for (QStringList::const_iterator it = arguments.constBegin(); it != acend; ++it) {
|
|
||||||
if (!app.sendMessage(prepareRemoteArgument(*it))) {
|
|
||||||
displayError(msgSendArgumentFailed());
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
// Special empty argument means: Show and raise (the slot just needs to be triggered)
|
|
||||||
if (!app.sendMessage(QString())) {
|
|
||||||
displayError(msgSendArgumentFailed());
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline QStringList getPluginPaths()
|
|
||||||
{
|
|
||||||
QStringList rc;
|
|
||||||
// Figure out root: Up one from 'bin'
|
|
||||||
QDir rootDir = QApplication::applicationDirPath();
|
|
||||||
rootDir.cdUp();
|
|
||||||
const QString rootDirPath = rootDir.canonicalPath();
|
|
||||||
// 1) "plugins" (Win/Linux)
|
|
||||||
QString pluginPath = rootDirPath;
|
|
||||||
pluginPath += QLatin1Char('/');
|
|
||||||
pluginPath += QLatin1String(GCS_LIBRARY_BASENAME);
|
|
||||||
pluginPath += QLatin1Char('/');
|
|
||||||
pluginPath += QLatin1String("openpilotgcs");
|
|
||||||
pluginPath += QLatin1Char('/');
|
|
||||||
pluginPath += QLatin1String("plugins");
|
|
||||||
rc.push_back(pluginPath);
|
|
||||||
// 2) "PlugIns" (OS X)
|
|
||||||
pluginPath = rootDirPath;
|
|
||||||
pluginPath += QLatin1Char('/');
|
|
||||||
pluginPath += QLatin1String("Plugins");
|
|
||||||
rc.push_back(pluginPath);
|
|
||||||
return rc;
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifdef Q_OS_MAC
|
#ifdef Q_OS_MAC
|
||||||
# define SHARE_PATH "/../Resources"
|
const QLatin1String SHARE_PATH("/../Resources");
|
||||||
#else
|
#else
|
||||||
# define SHARE_PATH "/../share/openpilotgcs"
|
const QLatin1String SHARE_PATH("/../share/openpilotgcs");
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static void overrideSettings(QSettings &settings, int argc, char **argv){
|
const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml";
|
||||||
|
|
||||||
QMap<QString, QString> settingOptions;
|
const char *fixedOptionsC = " [OPTION]... [FILE]...\n"
|
||||||
// Options like -DMy/setting=test
|
"Options:\n"
|
||||||
QRegExp rx("([^=]+)=(.*)");
|
" -help Display this help\n"
|
||||||
|
" -version Display application version\n"
|
||||||
|
" -no-splash Don't display splash screen\n"
|
||||||
|
" -client Attempt to connect to already running instance\n"
|
||||||
|
" -D <key>=<value> Permanently set a user setting, e.g: -D General/OverrideLanguage=de\n"
|
||||||
|
" -reset Reset user settings to factory defaults.\n"
|
||||||
|
" -config-file <file> Specify alternate factory defaults settings file (used with -reset)\n"
|
||||||
|
" -exit-after-config Exit after manipulating configuration settings\n";
|
||||||
|
|
||||||
for(int i = 0; i < argc; ++i ){
|
const QLatin1String HELP1_OPTION("-h");
|
||||||
if ( QString(CONFIG_OPTION).compare(QString(argv[i])) == 0 ){
|
const QLatin1String HELP2_OPTION("-help");
|
||||||
if ( rx.indexIn(argv[++i]) > -1 ){
|
const QLatin1String HELP3_OPTION("/h");
|
||||||
settingOptions.insert(rx.cap(1), rx.cap(2));
|
const QLatin1String HELP4_OPTION("--help");
|
||||||
|
const QLatin1String VERSION_OPTION("-version");
|
||||||
|
const QLatin1String NO_SPLASH_OPTION("-no-splash");
|
||||||
|
const QLatin1String CLIENT_OPTION("-client");
|
||||||
|
const QLatin1String CONFIG_OPTION("-D");
|
||||||
|
const QLatin1String RESET_OPTION("-reset");
|
||||||
|
const QLatin1String CONFIG_FILE_OPTION("-config-file");
|
||||||
|
const QLatin1String EXIT_AFTER_CONFIG_OPTION("-exit-after-config");
|
||||||
|
|
||||||
|
// Helpers for displaying messages. Note that there is no console on Windows.
|
||||||
|
void displayHelpText(QString t)
|
||||||
|
{
|
||||||
|
#ifdef Q_OS_WIN
|
||||||
|
// No console on Windows. (???)
|
||||||
|
// TODO there is a console on windows and popups are not always desired
|
||||||
|
t.replace(QLatin1Char('&'), QLatin1String("&"));
|
||||||
|
t.replace(QLatin1Char('<'), QLatin1String("<"));
|
||||||
|
t.replace(QLatin1Char('>'), QLatin1String(">"));
|
||||||
|
t.insert(0, QLatin1String("<html><pre>"));
|
||||||
|
t.append(QLatin1String("</pre></html>"));
|
||||||
|
QMessageBox::information(0, APP_NAME, t);
|
||||||
|
#else
|
||||||
|
qWarning("%s", qPrintable(t));
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void displayError(const QString &t)
|
||||||
|
{
|
||||||
|
#ifdef Q_OS_WIN
|
||||||
|
// No console on Windows. (???)
|
||||||
|
// TODO there is a console on windows and popups are not always desired
|
||||||
|
QMessageBox::critical(0, APP_NAME, t);
|
||||||
|
#else
|
||||||
|
qCritical("%s", qPrintable(t));
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void printVersion(const ExtensionSystem::PluginSpec *corePlugin, const ExtensionSystem::PluginManager &pm)
|
||||||
|
{
|
||||||
|
QString version;
|
||||||
|
QTextStream str(&version);
|
||||||
|
str << '\n' << APP_NAME << ' ' << corePlugin->version() << " based on Qt " << qVersion() << "\n\n";
|
||||||
|
pm.formatPluginVersions(str);
|
||||||
|
str << '\n' << corePlugin->copyright() << '\n';
|
||||||
|
displayHelpText(version);
|
||||||
|
}
|
||||||
|
|
||||||
|
void printHelp(const QString &appExecName, const ExtensionSystem::PluginManager &pm)
|
||||||
|
{
|
||||||
|
QString help;
|
||||||
|
QTextStream str(&help);
|
||||||
|
str << "Usage: " << appExecName << fixedOptionsC;
|
||||||
|
ExtensionSystem::PluginManager::formatOptions(str, OptionIndent, DescriptionIndent);
|
||||||
|
pm.formatPluginOptions(str, OptionIndent, DescriptionIndent);
|
||||||
|
displayHelpText(help);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline QString msgCoreLoadFailure(const QString &reason)
|
||||||
|
{
|
||||||
|
return QCoreApplication::translate("Application", "Failed to load core plug-in, reason is: %1").arg(reason);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline QString msgSendArgumentFailed()
|
||||||
|
{
|
||||||
|
return QCoreApplication::translate("Application",
|
||||||
|
"Unable to send command line arguments to the already running instance. It appears to be not responding.");
|
||||||
|
}
|
||||||
|
|
||||||
|
// Prepare a remote argument: If it is a relative file, add the current directory
|
||||||
|
// since the the central instance might be running in a different directory.
|
||||||
|
inline QString prepareRemoteArgument(const QString &arg)
|
||||||
|
{
|
||||||
|
QFileInfo fi(arg);
|
||||||
|
if (!fi.exists()) {
|
||||||
|
return arg;
|
||||||
|
}
|
||||||
|
if (fi.isRelative()) {
|
||||||
|
return fi.absoluteFilePath();
|
||||||
|
}
|
||||||
|
return arg;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Send the arguments to an already running instance of application
|
||||||
|
bool sendArguments(SharedTools::QtSingleApplication &app, const QStringList &arguments)
|
||||||
|
{
|
||||||
|
if (!arguments.empty()) {
|
||||||
|
// Send off arguments
|
||||||
|
const QStringList::const_iterator acend = arguments.constEnd();
|
||||||
|
for (QStringList::const_iterator it = arguments.constBegin(); it != acend; ++it) {
|
||||||
|
if (!app.sendMessage(prepareRemoteArgument(*it))) {
|
||||||
|
displayError(msgSendArgumentFailed());
|
||||||
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if ( QString(CLEAN_CONFIG_OPTION).compare(QString(argv[i])) == 0 ){
|
// Special empty argument means: Show and raise (the slot just needs to be triggered)
|
||||||
settings.clear();
|
if (!app.sendMessage(QString())) {
|
||||||
|
displayError(msgSendArgumentFailed());
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void systemInit()
|
||||||
|
{
|
||||||
|
#ifdef Q_OS_MAC
|
||||||
|
// increase the number of file that can be opened in application
|
||||||
|
struct rlimit rl;
|
||||||
|
getrlimit(RLIMIT_NOFILE, &rl);
|
||||||
|
rl.rlim_cur = rl.rlim_max;
|
||||||
|
setrlimit(RLIMIT_NOFILE, &rl);
|
||||||
|
#endif
|
||||||
|
#ifdef Q_OS_LINUX
|
||||||
|
QApplication::setAttribute(Qt::AA_X11InitThreads, true);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
inline QStringList getPluginPaths()
|
||||||
|
{
|
||||||
|
QStringList rc;
|
||||||
|
// Figure out root: Up one from 'bin'
|
||||||
|
QDir rootDir = QApplication::applicationDirPath();
|
||||||
|
rootDir.cdUp();
|
||||||
|
const QString rootDirPath = rootDir.canonicalPath();
|
||||||
|
// 1) "plugins" (Win/Linux)
|
||||||
|
QString pluginPath = rootDirPath;
|
||||||
|
pluginPath += QLatin1Char('/');
|
||||||
|
pluginPath += QLatin1String(GCS_LIBRARY_BASENAME);
|
||||||
|
pluginPath += QLatin1Char('/');
|
||||||
|
pluginPath += QLatin1String("openpilotgcs");
|
||||||
|
pluginPath += QLatin1Char('/');
|
||||||
|
pluginPath += QLatin1String("plugins");
|
||||||
|
rc.push_back(pluginPath);
|
||||||
|
// 2) "PlugIns" (OS X)
|
||||||
|
pluginPath = rootDirPath;
|
||||||
|
pluginPath += QLatin1Char('/');
|
||||||
|
pluginPath += QLatin1String("Plugins");
|
||||||
|
rc.push_back(pluginPath);
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
|
||||||
|
AppOptions options()
|
||||||
|
{
|
||||||
|
AppOptions appOptions;
|
||||||
|
appOptions.insert(HELP1_OPTION, false);
|
||||||
|
appOptions.insert(HELP2_OPTION, false);
|
||||||
|
appOptions.insert(HELP3_OPTION, false);
|
||||||
|
appOptions.insert(HELP4_OPTION, false);
|
||||||
|
appOptions.insert(VERSION_OPTION, false);
|
||||||
|
appOptions.insert(NO_SPLASH_OPTION, false);
|
||||||
|
appOptions.insert(CLIENT_OPTION, false);
|
||||||
|
appOptions.insert(CONFIG_OPTION, true);
|
||||||
|
appOptions.insert(RESET_OPTION, false);
|
||||||
|
appOptions.insert(CONFIG_FILE_OPTION, true);
|
||||||
|
appOptions.insert(EXIT_AFTER_CONFIG_OPTION, false);
|
||||||
|
return appOptions;
|
||||||
|
}
|
||||||
|
|
||||||
|
AppOptionValues parseCommandLine(SharedTools::QtSingleApplication &app,
|
||||||
|
ExtensionSystem::PluginManager &pluginManager, QString &errorMessage)
|
||||||
|
{
|
||||||
|
AppOptionValues appOptionValues;
|
||||||
|
const QStringList arguments = app.arguments();
|
||||||
|
if (arguments.size() > 1) {
|
||||||
|
AppOptions appOptions = options();
|
||||||
|
pluginManager.parseOptions(arguments, appOptions, &appOptionValues, &errorMessage);
|
||||||
|
}
|
||||||
|
return appOptionValues;
|
||||||
|
}
|
||||||
|
|
||||||
|
void loadFactoryDefaults(QSettings &settings, AppOptionValues &appOptionValues)
|
||||||
|
{
|
||||||
|
QDir directory(QCoreApplication::applicationDirPath() + SHARE_PATH + QString("/default_configurations"));
|
||||||
|
qDebug() << "Looking for factory defaults configuration files in:" << directory.absolutePath();
|
||||||
|
|
||||||
|
QString fileName;
|
||||||
|
|
||||||
|
// check if command line option -config-file contains a file name
|
||||||
|
QString commandLine = appOptionValues.value(CONFIG_FILE_OPTION);
|
||||||
|
if (!commandLine.isEmpty()) {
|
||||||
|
QFileInfo fi(commandLine);
|
||||||
|
if (fi.isRelative()) {
|
||||||
|
// file name specified on command line has a relative path
|
||||||
|
commandLine = directory.absolutePath() + QDir::separator() + commandLine;
|
||||||
|
}
|
||||||
|
if (QFile::exists(commandLine)) {
|
||||||
|
fileName = commandLine;
|
||||||
|
qDebug() << "Configuration file" << fileName << "specified on command line will be loaded.";
|
||||||
|
} else {
|
||||||
|
qWarning() << "Configuration file" << commandLine << "specified on command line does not exist.";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (fileName.isEmpty()) {
|
||||||
|
// check default file
|
||||||
|
if (QFile::exists(directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME)) {
|
||||||
|
// use default file name
|
||||||
|
fileName = directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME;
|
||||||
|
qDebug() << "Default configuration file" << fileName << "will be loaded.";
|
||||||
|
} else {
|
||||||
|
qWarning() << "No default configuration file found in" << directory.absolutePath();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (fileName.isEmpty()) {
|
||||||
|
// TODO should we exit violently?
|
||||||
|
qCritical() << "No default configuration file found!";
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// create settings from file
|
||||||
|
QSettings qs(fileName, XmlConfig::XmlSettingsFormat);
|
||||||
|
|
||||||
|
// transfer loaded settings to application settings
|
||||||
|
QStringList keys = qs.allKeys();
|
||||||
|
foreach(QString key, keys) {
|
||||||
|
settings.setValue(key, qs.value(key));
|
||||||
|
}
|
||||||
|
|
||||||
|
qDebug() << "Configuration file" << fileName << "was loaded.";
|
||||||
|
}
|
||||||
|
|
||||||
|
void overrideSettings(QSettings &settings, int argc, char **argv)
|
||||||
|
{
|
||||||
|
// Options like -D My/setting=test
|
||||||
|
QRegExp rx("([^=]+)=(.*)");
|
||||||
|
|
||||||
|
for (int i = 0; i < argc; ++i) {
|
||||||
|
if (CONFIG_OPTION == QString(argv[i])) {
|
||||||
|
if (rx.indexIn(argv[++i]) > -1) {
|
||||||
|
QString key = rx.cap(1);
|
||||||
|
QString value = rx.cap(2);
|
||||||
|
qDebug() << "User setting" << key << "set to value" << value;
|
||||||
|
settings.setValue(key, value);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
settings.sync();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loadTranslators(QString language, QTranslator &translator, QTranslator &qtTranslator)
|
||||||
|
{
|
||||||
|
const QString &creatorTrPath = QCoreApplication::applicationDirPath() + SHARE_PATH
|
||||||
|
+ QLatin1String("/translations");
|
||||||
|
if (translator.load(QLatin1String("openpilotgcs_") + language, creatorTrPath)) {
|
||||||
|
const QString &qtTrPath = QLibraryInfo::location(QLibraryInfo::TranslationsPath);
|
||||||
|
const QString &qtTrFile = QLatin1String("qt_") + language;
|
||||||
|
// Binary installer puts Qt tr files into creatorTrPath
|
||||||
|
if (qtTranslator.load(qtTrFile, qtTrPath) || qtTranslator.load(qtTrFile, creatorTrPath)) {
|
||||||
|
QCoreApplication::installTranslator(&translator);
|
||||||
|
QCoreApplication::installTranslator(&qtTranslator);
|
||||||
|
} else {
|
||||||
|
// unload()
|
||||||
|
translator.load(QString());
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
QList<QString> keys = settingOptions.keys();
|
} // namespace anonymous
|
||||||
foreach ( QString key, keys ){
|
|
||||||
settings.setValue(key, settingOptions.value(key));
|
|
||||||
}
|
|
||||||
settings.sync();
|
|
||||||
}
|
|
||||||
|
|
||||||
int main(int argc, char **argv)
|
int main(int argc, char **argv)
|
||||||
{
|
{
|
||||||
QElapsedTimer timer;
|
QElapsedTimer timer;
|
||||||
timer.start();
|
timer.start();
|
||||||
|
|
||||||
#ifdef Q_OS_MAC
|
// low level init
|
||||||
// increase the number of file that can be opened in OpenPilot GCS
|
systemInit();
|
||||||
struct rlimit rl;
|
|
||||||
getrlimit(RLIMIT_NOFILE, &rl);
|
|
||||||
rl.rlim_cur = rl.rlim_max;
|
|
||||||
setrlimit(RLIMIT_NOFILE, &rl);
|
|
||||||
#endif
|
|
||||||
#ifdef Q_OS_LINUX
|
|
||||||
QApplication::setAttribute(Qt::AA_X11InitThreads, true);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//Set the default locale to EN, if this is not set the system locale will be used
|
// create application
|
||||||
//and as of now we dont want that behaviour.
|
SharedTools::QtSingleApplication app(APP_NAME, argc, argv);
|
||||||
QLocale::setDefault(QLocale::English);
|
|
||||||
|
|
||||||
SharedTools::QtSingleApplication app((QLatin1String(appNameC)), argc, argv);
|
// initialize the plugin manager
|
||||||
|
|
||||||
//Open Splashscreen
|
|
||||||
GCSSplashScreen splash;
|
|
||||||
splash.show();
|
|
||||||
|
|
||||||
QString locale = QLocale::system().name();
|
|
||||||
|
|
||||||
// Must be done before any QSettings class is created
|
|
||||||
QSettings::setPath(XmlConfig::XmlSettingsFormat, QSettings::SystemScope,
|
|
||||||
QCoreApplication::applicationDirPath()+QLatin1String(SHARE_PATH));
|
|
||||||
// keep this in sync with the MainWindow ctor in coreplugin/mainwindow.cpp
|
|
||||||
QSettings settings(XmlConfig::XmlSettingsFormat, QSettings::UserScope,
|
|
||||||
QLatin1String("OpenPilot"), QLatin1String("OpenPilotGCS_config"));
|
|
||||||
|
|
||||||
overrideSettings(settings, argc, argv);
|
|
||||||
locale = settings.value("General/OverrideLanguage", locale).toString();
|
|
||||||
|
|
||||||
QTranslator translator;
|
|
||||||
QTranslator qtTranslator;
|
|
||||||
|
|
||||||
const QString &creatorTrPath = QCoreApplication::applicationDirPath()
|
|
||||||
+ QLatin1String(SHARE_PATH "/translations");
|
|
||||||
if (translator.load(QLatin1String("openpilotgcs_") + locale, creatorTrPath)) {
|
|
||||||
const QString &qtTrPath = QLibraryInfo::location(QLibraryInfo::TranslationsPath);
|
|
||||||
const QString &qtTrFile = QLatin1String("qt_") + locale;
|
|
||||||
// Binary installer puts Qt tr files into creatorTrPath
|
|
||||||
if (qtTranslator.load(qtTrFile, qtTrPath) || qtTranslator.load(qtTrFile, creatorTrPath)) {
|
|
||||||
QCoreApplication::installTranslator(&translator);
|
|
||||||
QCoreApplication::installTranslator(&qtTranslator);
|
|
||||||
} else {
|
|
||||||
translator.load(QString()); // unload()
|
|
||||||
}
|
|
||||||
}
|
|
||||||
app.setProperty("qtc_locale", locale); // Do we need this?
|
|
||||||
|
|
||||||
splash.showProgressMessage(QObject::tr("Application starting..."));
|
|
||||||
|
|
||||||
// Load
|
|
||||||
ExtensionSystem::PluginManager pluginManager;
|
ExtensionSystem::PluginManager pluginManager;
|
||||||
pluginManager.setFileExtension(QLatin1String("pluginspec"));
|
pluginManager.setFileExtension(QLatin1String("pluginspec"));
|
||||||
|
pluginManager.setPluginPaths(getPluginPaths());
|
||||||
|
|
||||||
const QStringList pluginPaths = getPluginPaths();
|
// parse command line
|
||||||
pluginManager.setPluginPaths(pluginPaths);
|
qDebug() << "Command line" << app.arguments();
|
||||||
|
QString errorMessage;
|
||||||
const QStringList arguments = app.arguments();
|
AppOptionValues appOptionValues = parseCommandLine(app, pluginManager, errorMessage);
|
||||||
QMap<QString, QString> foundAppOptions;
|
if (!errorMessage.isEmpty()) {
|
||||||
if (arguments.size() > 1) {
|
// this will display two popups : one error popup + one usage string popup
|
||||||
QMap<QString, bool> appOptions;
|
// TODO merge two popups into one.
|
||||||
appOptions.insert(QLatin1String(HELP_OPTION1), false);
|
displayError(errorMessage);
|
||||||
appOptions.insert(QLatin1String(HELP_OPTION2), false);
|
printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager);
|
||||||
appOptions.insert(QLatin1String(HELP_OPTION3), false);
|
return -1;
|
||||||
appOptions.insert(QLatin1String(HELP_OPTION4), false);
|
|
||||||
appOptions.insert(QLatin1String(VERSION_OPTION), false);
|
|
||||||
appOptions.insert(QLatin1String(CLIENT_OPTION), false);
|
|
||||||
appOptions.insert(QLatin1String(CONFIG_OPTION), true);
|
|
||||||
appOptions.insert(QLatin1String(CLEAN_CONFIG_OPTION), false);
|
|
||||||
appOptions.insert(QLatin1String(EXIT_AFTER_CONFIG_OPTION), false);
|
|
||||||
QString errorMessage;
|
|
||||||
if (!pluginManager.parseOptions(arguments,
|
|
||||||
appOptions,
|
|
||||||
&foundAppOptions,
|
|
||||||
&errorMessage)) {
|
|
||||||
displayError(errorMessage);
|
|
||||||
printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager);
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// load user settings
|
||||||
|
// Must be done before any QSettings class is created
|
||||||
|
// keep this in sync with the MainWindow ctor in coreplugin/mainwindow.cpp
|
||||||
|
QString settingsPath = QCoreApplication::applicationDirPath() + SHARE_PATH;
|
||||||
|
qDebug() << "Loading system settings from" << settingsPath;
|
||||||
|
QSettings::setPath(XmlConfig::XmlSettingsFormat, QSettings::SystemScope, settingsPath);
|
||||||
|
qDebug() << "Loading user settings from" << SETTINGS_ORG_NAME << "/" << SETTINGS_APP_NAME;
|
||||||
|
QSettings settings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, SETTINGS_ORG_NAME, SETTINGS_APP_NAME);
|
||||||
|
|
||||||
|
// need to reset all user settings?
|
||||||
|
if (appOptionValues.contains(RESET_OPTION)) {
|
||||||
|
qDebug() << "Resetting user settings!";
|
||||||
|
settings.clear();
|
||||||
|
}
|
||||||
|
|
||||||
|
// check if we have user settings
|
||||||
|
if (!settings.allKeys().count()) {
|
||||||
|
// no user settings, load the factory defaults
|
||||||
|
qDebug() << "No user settings found, loading factory defaults...";
|
||||||
|
loadFactoryDefaults(settings, appOptionValues);
|
||||||
|
}
|
||||||
|
|
||||||
|
// override settings with command line provided values
|
||||||
|
// take notice that the overridden values will be saved in the user settings and will continue to be effective
|
||||||
|
// in subsequent GCS runs
|
||||||
|
overrideSettings(settings, argc, argv);
|
||||||
|
|
||||||
|
// initialize GCS locale
|
||||||
|
// use the value defined by the General/Locale setting or default to system Locale.
|
||||||
|
// the General/Locale setting is not available in the Options dialog, it is a hidden setting but can still be changed:
|
||||||
|
// - through the command line
|
||||||
|
// - editing the factory defaults XML file before 1st launch
|
||||||
|
// - editing the user XML file
|
||||||
|
QString localeName = settings.value("General/Locale", QLocale::system().name()).toString();
|
||||||
|
QLocale::setDefault(localeName);
|
||||||
|
|
||||||
|
// some debugging
|
||||||
|
qDebug() << "main - system locale:" << QLocale::system().name();
|
||||||
|
qDebug() << "main - GCS locale:" << QLocale().name();
|
||||||
|
|
||||||
|
// load translation file
|
||||||
|
// the language used is defined by the General/OverrideLanguage setting (defaults to GCS locale)
|
||||||
|
// if the translation file for the given language is not found, GCS will default to built in English.
|
||||||
|
QString language = settings.value("General/OverrideLanguage", localeName).toString();
|
||||||
|
qDebug() << "main - language:" << language;
|
||||||
|
QTranslator translator;
|
||||||
|
QTranslator qtTranslator;
|
||||||
|
loadTranslators(language, translator, qtTranslator);
|
||||||
|
|
||||||
|
app.setProperty("qtc_locale", localeName); // Do we need this?
|
||||||
|
|
||||||
|
if (appOptionValues.contains(EXIT_AFTER_CONFIG_OPTION)) {
|
||||||
|
qDebug() << "main - exiting after config!";
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// open the splash screen
|
||||||
|
GCSSplashScreen *splash = 0;
|
||||||
|
if (!appOptionValues.contains(NO_SPLASH_OPTION)) {
|
||||||
|
splash = new GCSSplashScreen();
|
||||||
|
// show splash
|
||||||
|
splash->showProgressMessage(QObject::tr("Application starting..."));
|
||||||
|
splash->show();
|
||||||
|
// connect to track progress of plugin manager
|
||||||
|
QObject::connect(&pluginManager, SIGNAL(pluginAboutToBeLoaded(ExtensionSystem::PluginSpec*)), splash,
|
||||||
|
SLOT(showPluginLoadingProgress(ExtensionSystem::PluginSpec*)));
|
||||||
|
}
|
||||||
|
|
||||||
|
// find and load core plugin
|
||||||
const PluginSpecSet plugins = pluginManager.plugins();
|
const PluginSpecSet plugins = pluginManager.plugins();
|
||||||
ExtensionSystem::PluginSpec *coreplugin = 0;
|
ExtensionSystem::PluginSpec *coreplugin = 0;
|
||||||
foreach (ExtensionSystem::PluginSpec *spec, plugins) {
|
foreach (ExtensionSystem::PluginSpec *spec, plugins) {
|
||||||
if (spec->name() == QLatin1String(corePluginNameC)) {
|
if (spec->name() == CORE_PLUGIN_NAME) {
|
||||||
coreplugin = spec;
|
coreplugin = spec;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if(!coreplugin){
|
if (!coreplugin) {
|
||||||
QString nativePaths = QDir::toNativeSeparators(pluginPaths.join(QLatin1String(",")));
|
QString nativePaths = QDir::toNativeSeparators(getPluginPaths().join(QLatin1String(",")));
|
||||||
const QString reason = QCoreApplication::translate("Application", "Could not find 'Core.pluginspec' in %1").arg(nativePaths);
|
const QString reason = QCoreApplication::translate("Application", "Could not find 'Core.pluginspec' in %1").arg(
|
||||||
|
nativePaths);
|
||||||
displayError(msgCoreLoadFailure(reason));
|
displayError(msgCoreLoadFailure(reason));
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
@ -341,26 +516,21 @@ int main(int argc, char **argv)
|
|||||||
displayError(msgCoreLoadFailure(coreplugin->errorString()));
|
displayError(msgCoreLoadFailure(coreplugin->errorString()));
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
if (foundAppOptions.contains(QLatin1String(VERSION_OPTION))) {
|
|
||||||
|
if (appOptionValues.contains(VERSION_OPTION)) {
|
||||||
printVersion(coreplugin, pluginManager);
|
printVersion(coreplugin, pluginManager);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
if (foundAppOptions.contains(QLatin1String(EXIT_AFTER_CONFIG_OPTION))) {
|
if (appOptionValues.contains(HELP1_OPTION) || appOptionValues.contains(HELP2_OPTION)
|
||||||
return 0;
|
|| appOptionValues.contains(HELP3_OPTION) || appOptionValues.contains(HELP4_OPTION)) {
|
||||||
}
|
|
||||||
if (foundAppOptions.contains(QLatin1String(HELP_OPTION1))
|
|
||||||
|| foundAppOptions.contains(QLatin1String(HELP_OPTION2))
|
|
||||||
|| foundAppOptions.contains(QLatin1String(HELP_OPTION3))
|
|
||||||
|| foundAppOptions.contains(QLatin1String(HELP_OPTION4))) {
|
|
||||||
printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager);
|
printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
const bool isFirstInstance = !app.isRunning();
|
|
||||||
if (!isFirstInstance && foundAppOptions.contains(QLatin1String(CLIENT_OPTION)))
|
|
||||||
return sendArguments(app, pluginManager.arguments()) ? 0 : -1;
|
|
||||||
|
|
||||||
QObject::connect(&pluginManager, SIGNAL(pluginAboutToBeLoaded(ExtensionSystem::PluginSpec*)),
|
const bool isFirstInstance = !app.isRunning();
|
||||||
&splash, SLOT(showPluginLoadingProgress(ExtensionSystem::PluginSpec*)));
|
if (!isFirstInstance && appOptionValues.contains(CLIENT_OPTION)) {
|
||||||
|
return sendArguments(app, pluginManager.arguments()) ? 0 : -1;
|
||||||
|
}
|
||||||
|
|
||||||
pluginManager.loadPlugins();
|
pluginManager.loadPlugins();
|
||||||
|
|
||||||
@ -371,19 +541,21 @@ int main(int argc, char **argv)
|
|||||||
|
|
||||||
{
|
{
|
||||||
QStringList errors;
|
QStringList errors;
|
||||||
foreach (ExtensionSystem::PluginSpec *p, pluginManager.plugins())
|
foreach (ExtensionSystem::PluginSpec *p, pluginManager.plugins()) {
|
||||||
if (p->hasError())
|
if (p->hasError()) {
|
||||||
errors.append(p->errorString());
|
errors.append(p->errorString());
|
||||||
if (!errors.isEmpty())
|
}
|
||||||
|
}
|
||||||
|
if (!errors.isEmpty()) {
|
||||||
QMessageBox::warning(0,
|
QMessageBox::warning(0,
|
||||||
QCoreApplication::translate("Application", "OpenPilot GCS - Plugin loader messages"),
|
QCoreApplication::translate("Application", "OpenPilot GCS - Plugin loader messages"),
|
||||||
errors.join(QString::fromLatin1("\n\n")));
|
errors.join(QString::fromLatin1("\n\n")));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (isFirstInstance) {
|
if (isFirstInstance) {
|
||||||
// Set up lock and remote arguments for the first instance only.
|
// Set up lock and remote arguments for the first instance only.
|
||||||
// Silently fallback to unconnected instances for any subsequent
|
// Silently fallback to unconnected instances for any subsequent instances.
|
||||||
// instances.
|
|
||||||
app.initialize();
|
app.initialize();
|
||||||
QObject::connect(&app, SIGNAL(messageReceived(QString)), coreplugin->plugin(), SLOT(remoteArgument(QString)));
|
QObject::connect(&app, SIGNAL(messageReceived(QString)), coreplugin->plugin(), SLOT(remoteArgument(QString)));
|
||||||
}
|
}
|
||||||
@ -392,15 +564,17 @@ int main(int argc, char **argv)
|
|||||||
// Do this after the event loop has started
|
// Do this after the event loop has started
|
||||||
QTimer::singleShot(100, &pluginManager, SLOT(startTests()));
|
QTimer::singleShot(100, &pluginManager, SLOT(startTests()));
|
||||||
|
|
||||||
//Update message and postpone closing of splashscreen 3 seconds
|
if (splash) {
|
||||||
splash.showProgressMessage(QObject::tr("Application started."));
|
// close and delete splash
|
||||||
QTimer::singleShot(1500, &splash, SLOT(close()));
|
splash->close();
|
||||||
|
delete splash;
|
||||||
|
}
|
||||||
|
|
||||||
qDebug() << "main() took" << timer.elapsed() << "ms";
|
qDebug() << "main - main took" << timer.elapsed() << "ms";
|
||||||
|
|
||||||
int ret = app.exec();
|
int ret = app.exec();
|
||||||
|
|
||||||
qDebug() << "GCS ran for" << timer.elapsed() << "ms";
|
qDebug() << "main - GCS ran for" << timer.elapsed() << "ms";
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
@ -125,23 +125,23 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
|||||||
connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack()));
|
connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack()));
|
||||||
|
|
||||||
m_config->stackedWidget->setCurrentIndex(0);
|
m_config->stackedWidget->setCurrentIndex(0);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0,1,true);
|
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos1, 0, 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1,1,true);
|
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos2, 1, 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2,1,true);
|
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos3, 2, 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,3,1,true);
|
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos4, 3, 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,4,1,true);
|
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos5, 4, 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5,1,true);
|
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModePosition", m_config->fmsModePos6, 5, 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModeNumber",m_config->fmsPosNum);
|
addUAVObjectToWidgetRelation("ManualControlSettings", "FlightModeNumber", m_config->fmsPosNum);
|
||||||
|
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll");
|
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Roll, "Roll", 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Roll,"Roll");
|
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Roll, "Roll", 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Roll,"Roll");
|
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Roll, "Roll", 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Pitch,"Pitch");
|
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Pitch, "Pitch", 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Pitch,"Pitch");
|
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Pitch, "Pitch", 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Pitch,"Pitch");
|
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Pitch, "Pitch", 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Yaw,"Yaw");
|
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization1Settings", m_config->fmsSsPos1Yaw, "Yaw", 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Yaw,"Yaw");
|
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization2Settings", m_config->fmsSsPos2Yaw, "Yaw", 1, true);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Yaw,"Yaw");
|
addUAVObjectToWidgetRelation("ManualControlSettings", "Stabilization3Settings", m_config->fmsSsPos3Yaw, "Yaw", 1, true);
|
||||||
|
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl);
|
addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl);
|
||||||
addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000);
|
addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000);
|
||||||
|
@ -64,7 +64,8 @@
|
|||||||
<file>images/tx-rx.svg</file>
|
<file>images/tx-rx.svg</file>
|
||||||
<file>qml/images/tab.png</file>
|
<file>qml/images/tab.png</file>
|
||||||
<file>qml/AboutDialog.qml</file>
|
<file>qml/AboutDialog.qml</file>
|
||||||
<file>qml/FlickableWebView.qml</file>
|
<file>qml/AuthorsModel.qml</file>
|
||||||
|
<file>qml/ScrollDecorator.qml</file>
|
||||||
<file>qml/TabWidget.qml</file>
|
<file>qml/TabWidget.qml</file>
|
||||||
</qresource>
|
</qresource>
|
||||||
</RCC>
|
</RCC>
|
||||||
|
@ -1,22 +1,27 @@
|
|||||||
TEMPLATE = lib
|
TEMPLATE = lib
|
||||||
TARGET = Core
|
TARGET = Core
|
||||||
DEFINES += CORE_LIBRARY
|
DEFINES += CORE_LIBRARY
|
||||||
|
|
||||||
QT += declarative \
|
QT += declarative \
|
||||||
xml \
|
xml \
|
||||||
network \
|
network \
|
||||||
script \
|
script \
|
||||||
svg \
|
svg \
|
||||||
sql
|
sql
|
||||||
|
|
||||||
include(../../openpilotgcsplugin.pri)
|
include(../../openpilotgcsplugin.pri)
|
||||||
include(../../libs/utils/utils.pri)
|
include(../../libs/utils/utils.pri)
|
||||||
include(../../shared/scriptwrapper/scriptwrapper.pri)
|
include(../../shared/scriptwrapper/scriptwrapper.pri)
|
||||||
include(coreplugin_dependencies.pri)
|
include(coreplugin_dependencies.pri)
|
||||||
|
|
||||||
INCLUDEPATH += dialogs \
|
INCLUDEPATH += dialogs \
|
||||||
uavgadgetmanager \
|
uavgadgetmanager \
|
||||||
actionmanager
|
actionmanager
|
||||||
|
|
||||||
DEPENDPATH += dialogs \
|
DEPENDPATH += dialogs \
|
||||||
uavgadgetmanager \
|
uavgadgetmanager \
|
||||||
actionmanager
|
actionmanager
|
||||||
|
|
||||||
SOURCES += mainwindow.cpp \
|
SOURCES += mainwindow.cpp \
|
||||||
tabpositionindicator.cpp \
|
tabpositionindicator.cpp \
|
||||||
fancyactionbar.cpp \
|
fancyactionbar.cpp \
|
||||||
@ -64,8 +69,8 @@ SOURCES += mainwindow.cpp \
|
|||||||
workspacesettings.cpp \
|
workspacesettings.cpp \
|
||||||
uavconfiginfo.cpp \
|
uavconfiginfo.cpp \
|
||||||
authorsdialog.cpp \
|
authorsdialog.cpp \
|
||||||
telemetrymonitorwidget.cpp \
|
telemetrymonitorwidget.cpp
|
||||||
dialogs/importsettings.cpp
|
|
||||||
HEADERS += mainwindow.h \
|
HEADERS += mainwindow.h \
|
||||||
tabpositionindicator.h \
|
tabpositionindicator.h \
|
||||||
fancyactionbar.h \
|
fancyactionbar.h \
|
||||||
@ -126,20 +131,22 @@ HEADERS += mainwindow.h \
|
|||||||
uavconfiginfo.h \
|
uavconfiginfo.h \
|
||||||
authorsdialog.h \
|
authorsdialog.h \
|
||||||
iconfigurableplugin.h \
|
iconfigurableplugin.h \
|
||||||
telemetrymonitorwidget.h \
|
telemetrymonitorwidget.h
|
||||||
dialogs/importsettings.h
|
|
||||||
FORMS += dialogs/settingsdialog.ui \
|
FORMS += dialogs/settingsdialog.ui \
|
||||||
dialogs/shortcutsettings.ui \
|
dialogs/shortcutsettings.ui \
|
||||||
generalsettings.ui \
|
generalsettings.ui \
|
||||||
uavgadgetoptionspage.ui \
|
uavgadgetoptionspage.ui \
|
||||||
workspacesettings.ui \
|
workspacesettings.ui
|
||||||
dialogs/importsettings.ui
|
|
||||||
RESOURCES += core.qrc \
|
RESOURCES += core.qrc \
|
||||||
fancyactionbar.qrc
|
fancyactionbar.qrc
|
||||||
|
|
||||||
unix:!macx {
|
unix:!macx {
|
||||||
images.files = images/openpilot_logo_*.png
|
images.files = images/openpilot_logo_*.png
|
||||||
images.files = images/qtcreator_logo_*.png
|
images.files = images/qtcreator_logo_*.png
|
||||||
images.path = /share/pixmaps
|
images.path = /share/pixmaps
|
||||||
INSTALLS += images
|
INSTALLS += images
|
||||||
}
|
}
|
||||||
|
|
||||||
OTHER_FILES += Core.pluginspec
|
OTHER_FILES += Core.pluginspec
|
||||||
|
@ -1,57 +0,0 @@
|
|||||||
#include "importsettings.h"
|
|
||||||
#include "ui_importsettings.h"
|
|
||||||
#include <QDir>
|
|
||||||
#include <QSettings>
|
|
||||||
#include <utils/xmlconfig.h>
|
|
||||||
#include <QTimer>
|
|
||||||
|
|
||||||
importSettings::importSettings(QWidget *parent) :
|
|
||||||
QDialog(parent),
|
|
||||||
ui(new Ui::importSettings)
|
|
||||||
{
|
|
||||||
ui->setupUi(this);
|
|
||||||
connect(ui->cbConfigs, SIGNAL(currentIndexChanged(int)), this, SLOT(updateDetails(int)));
|
|
||||||
connect(ui->btnLoad, SIGNAL(clicked()), this, SLOT(accept()));
|
|
||||||
QTimer::singleShot(500, this, SLOT(repaint()));
|
|
||||||
}
|
|
||||||
|
|
||||||
void importSettings::loadFiles(QString path)
|
|
||||||
{
|
|
||||||
QDir myDir(path);
|
|
||||||
QStringList filters;
|
|
||||||
filters << "*.xml";
|
|
||||||
QStringList list = myDir.entryList(filters,QDir::Files);
|
|
||||||
int x = 0;
|
|
||||||
foreach(QString fileStr, list) {
|
|
||||||
fileInfo *info = new fileInfo;
|
|
||||||
QSettings settings(path+QDir::separator() + fileStr, XmlConfig::XmlSettingsFormat);
|
|
||||||
settings.beginGroup("General");
|
|
||||||
info->description = settings.value("Description", "None").toString();
|
|
||||||
info->details = settings.value("Details", "None").toString();
|
|
||||||
settings.endGroup();
|
|
||||||
info->file = path + QDir::separator() + fileStr;
|
|
||||||
configList.insert(x,info);
|
|
||||||
ui->cbConfigs->addItem(info->description, x);
|
|
||||||
++x;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void importSettings::updateDetails(int index)
|
|
||||||
{
|
|
||||||
fileInfo *info = configList.value(ui->cbConfigs->itemData(index).toInt());
|
|
||||||
ui->lblDetails->setText(info->details);
|
|
||||||
}
|
|
||||||
|
|
||||||
QString importSettings::choosenConfig()
|
|
||||||
{
|
|
||||||
fileInfo *info = configList.value(ui->cbConfigs->itemData(ui->cbConfigs->currentIndex()).toInt());
|
|
||||||
return info->file;
|
|
||||||
}
|
|
||||||
|
|
||||||
importSettings::~importSettings()
|
|
||||||
{
|
|
||||||
foreach(fileInfo * info,configList.values()) {
|
|
||||||
delete info;
|
|
||||||
}
|
|
||||||
delete ui;
|
|
||||||
}
|
|
@ -1,35 +0,0 @@
|
|||||||
|
|
||||||
#ifndef IMPORTSETTINGS_H
|
|
||||||
#define IMPORTSETTINGS_H
|
|
||||||
|
|
||||||
#include <QDialog>
|
|
||||||
#include <QMap>
|
|
||||||
namespace Ui {
|
|
||||||
class importSettings;
|
|
||||||
}
|
|
||||||
|
|
||||||
class importSettings : public QDialog
|
|
||||||
{
|
|
||||||
Q_OBJECT
|
|
||||||
struct fileInfo {
|
|
||||||
QString file;
|
|
||||||
QString description;
|
|
||||||
QString details;
|
|
||||||
};
|
|
||||||
|
|
||||||
public:
|
|
||||||
explicit importSettings(QWidget *parent = 0);
|
|
||||||
~importSettings();
|
|
||||||
|
|
||||||
void loadFiles(QString path);
|
|
||||||
QString choosenConfig();
|
|
||||||
|
|
||||||
private:
|
|
||||||
Ui::importSettings *ui;
|
|
||||||
QMap<int,fileInfo*> configList;
|
|
||||||
|
|
||||||
private slots:
|
|
||||||
void updateDetails(int);
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif // IMPORTSETTINGS_H
|
|
@ -1,82 +0,0 @@
|
|||||||
<?xml version="1.0" encoding="UTF-8"?>
|
|
||||||
<ui version="4.0">
|
|
||||||
<class>importSettings</class>
|
|
||||||
<widget class="QDialog" name="importSettings">
|
|
||||||
<property name="geometry">
|
|
||||||
<rect>
|
|
||||||
<x>0</x>
|
|
||||||
<y>0</y>
|
|
||||||
<width>373</width>
|
|
||||||
<height>167</height>
|
|
||||||
</rect>
|
|
||||||
</property>
|
|
||||||
<property name="windowTitle">
|
|
||||||
<string>OpenPilotGCS</string>
|
|
||||||
</property>
|
|
||||||
<layout class="QVBoxLayout" name="verticalLayout">
|
|
||||||
<item>
|
|
||||||
<widget class="QLabel" name="label">
|
|
||||||
<property name="text">
|
|
||||||
<string>No configuration file could be found.
|
|
||||||
Please choose from one of the default configurations</string>
|
|
||||||
</property>
|
|
||||||
<property name="scaledContents">
|
|
||||||
<bool>false</bool>
|
|
||||||
</property>
|
|
||||||
<property name="alignment">
|
|
||||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
|
||||||
</property>
|
|
||||||
</widget>
|
|
||||||
</item>
|
|
||||||
<item>
|
|
||||||
<widget class="QComboBox" name="cbConfigs"/>
|
|
||||||
</item>
|
|
||||||
<item>
|
|
||||||
<widget class="QLabel" name="lblDetails">
|
|
||||||
<property name="text">
|
|
||||||
<string>TextLabel</string>
|
|
||||||
</property>
|
|
||||||
</widget>
|
|
||||||
</item>
|
|
||||||
<item>
|
|
||||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
|
||||||
<item>
|
|
||||||
<spacer name="horizontalSpacer">
|
|
||||||
<property name="orientation">
|
|
||||||
<enum>Qt::Horizontal</enum>
|
|
||||||
</property>
|
|
||||||
<property name="sizeHint" stdset="0">
|
|
||||||
<size>
|
|
||||||
<width>40</width>
|
|
||||||
<height>20</height>
|
|
||||||
</size>
|
|
||||||
</property>
|
|
||||||
</spacer>
|
|
||||||
</item>
|
|
||||||
<item>
|
|
||||||
<widget class="QPushButton" name="btnLoad">
|
|
||||||
<property name="text">
|
|
||||||
<string>Load</string>
|
|
||||||
</property>
|
|
||||||
</widget>
|
|
||||||
</item>
|
|
||||||
<item>
|
|
||||||
<spacer name="horizontalSpacer_2">
|
|
||||||
<property name="orientation">
|
|
||||||
<enum>Qt::Horizontal</enum>
|
|
||||||
</property>
|
|
||||||
<property name="sizeHint" stdset="0">
|
|
||||||
<size>
|
|
||||||
<width>40</width>
|
|
||||||
<height>20</height>
|
|
||||||
</size>
|
|
||||||
</property>
|
|
||||||
</spacer>
|
|
||||||
</item>
|
|
||||||
</layout>
|
|
||||||
</item>
|
|
||||||
</layout>
|
|
||||||
</widget>
|
|
||||||
<resources/>
|
|
||||||
<connections/>
|
|
||||||
</ui>
|
|
@ -45,11 +45,11 @@ using namespace Core::Internal;
|
|||||||
|
|
||||||
GeneralSettings::GeneralSettings():
|
GeneralSettings::GeneralSettings():
|
||||||
m_saveSettingsOnExit(true),
|
m_saveSettingsOnExit(true),
|
||||||
m_dialog(0),
|
|
||||||
m_autoConnect(true),
|
m_autoConnect(true),
|
||||||
m_autoSelect(true),
|
m_autoSelect(true),
|
||||||
m_useUDPMirror(false),
|
m_useUDPMirror(false),
|
||||||
m_useExpertMode(false)
|
m_useExpertMode(false),
|
||||||
|
m_dialog(0)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -88,23 +88,23 @@ void GeneralSettings::fillLanguageBox() const
|
|||||||
m_page->languageBox->addItem(tr("<System Language>"), QString());
|
m_page->languageBox->addItem(tr("<System Language>"), QString());
|
||||||
// need to add this explicitly, since there is no qm file for English
|
// need to add this explicitly, since there is no qm file for English
|
||||||
m_page->languageBox->addItem(QLatin1String("English"), QLatin1String("C"));
|
m_page->languageBox->addItem(QLatin1String("English"), QLatin1String("C"));
|
||||||
if (currentLocale == QLatin1String("C"))
|
if (currentLocale == QLatin1String("C")) {
|
||||||
m_page->languageBox->setCurrentIndex(m_page->languageBox->count() - 1);
|
m_page->languageBox->setCurrentIndex(m_page->languageBox->count() - 1);
|
||||||
|
}
|
||||||
|
|
||||||
const QString creatorTrPath =
|
const QString creatorTrPath = Core::ICore::instance()->resourcePath() + QLatin1String("/translations");
|
||||||
Core::ICore::instance()->resourcePath() + QLatin1String("/translations");
|
|
||||||
const QStringList languageFiles = QDir(creatorTrPath).entryList(QStringList(QLatin1String("openpilotgcs*.qm")));
|
const QStringList languageFiles = QDir(creatorTrPath).entryList(QStringList(QLatin1String("openpilotgcs*.qm")));
|
||||||
|
|
||||||
Q_FOREACH(const QString &languageFile, languageFiles)
|
foreach(QString languageFile, languageFiles) {
|
||||||
{
|
int start = languageFile.indexOf(QLatin1Char('_')) + 1;
|
||||||
int start = languageFile.indexOf(QLatin1Char('_'))+1;
|
|
||||||
int end = languageFile.lastIndexOf(QLatin1Char('.'));
|
int end = languageFile.lastIndexOf(QLatin1Char('.'));
|
||||||
const QString locale = languageFile.mid(start, end-start);
|
const QString locale = languageFile.mid(start, end - start);
|
||||||
// no need to show a language that creator will not load anyway
|
// no need to show a language that creator will not load anyway
|
||||||
if (hasQmFilesForLocale(locale, creatorTrPath)) {
|
if (hasQmFilesForLocale(locale, creatorTrPath)) {
|
||||||
m_page->languageBox->addItem(QLocale::languageToString(QLocale(locale).language()), locale);
|
m_page->languageBox->addItem(QLocale::languageToString(QLocale(locale).language()), locale);
|
||||||
if (locale == currentLocale)
|
if (locale == currentLocale) {
|
||||||
m_page->languageBox->setCurrentIndex(m_page->languageBox->count() - 1);
|
m_page->languageBox->setCurrentIndex(m_page->languageBox->count() - 1);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -114,8 +114,11 @@ QWidget *GeneralSettings::createPage(QWidget *parent)
|
|||||||
m_page = new Ui::GeneralSettings();
|
m_page = new Ui::GeneralSettings();
|
||||||
QWidget *w = new QWidget(parent);
|
QWidget *w = new QWidget(parent);
|
||||||
m_page->setupUi(w);
|
m_page->setupUi(w);
|
||||||
|
|
||||||
fillLanguageBox();
|
fillLanguageBox();
|
||||||
connect(m_page->checkAutoConnect,SIGNAL(stateChanged(int)),this,SLOT(slotAutoConnect(int)));
|
|
||||||
|
connect(m_page->checkAutoConnect, SIGNAL(stateChanged(int)), this, SLOT(slotAutoConnect(int)));
|
||||||
|
|
||||||
m_page->checkBoxSaveOnExit->setChecked(m_saveSettingsOnExit);
|
m_page->checkBoxSaveOnExit->setChecked(m_saveSettingsOnExit);
|
||||||
m_page->checkAutoConnect->setChecked(m_autoConnect);
|
m_page->checkAutoConnect->setChecked(m_autoConnect);
|
||||||
m_page->checkAutoSelect->setChecked(m_autoSelect);
|
m_page->checkAutoSelect->setChecked(m_autoSelect);
|
||||||
@ -123,8 +126,7 @@ QWidget *GeneralSettings::createPage(QWidget *parent)
|
|||||||
m_page->cbExpertMode->setChecked(m_useExpertMode);
|
m_page->cbExpertMode->setChecked(m_useExpertMode);
|
||||||
m_page->colorButton->setColor(StyleHelper::baseColor());
|
m_page->colorButton->setColor(StyleHelper::baseColor());
|
||||||
|
|
||||||
connect(m_page->resetButton, SIGNAL(clicked()),
|
connect(m_page->resetButton, SIGNAL(clicked()), this, SLOT(resetInterfaceColor()));
|
||||||
this, SLOT(resetInterfaceColor()));
|
|
||||||
|
|
||||||
return w;
|
return w;
|
||||||
}
|
}
|
||||||
@ -148,26 +150,28 @@ void GeneralSettings::finish()
|
|||||||
delete m_page;
|
delete m_page;
|
||||||
}
|
}
|
||||||
|
|
||||||
void GeneralSettings::readSettings(QSettings* qs)
|
void GeneralSettings::readSettings(QSettings *qs)
|
||||||
{
|
{
|
||||||
qs->beginGroup(QLatin1String("General"));
|
qs->beginGroup(QLatin1String("General"));
|
||||||
m_language = qs->value(QLatin1String("OverrideLanguage"),QLocale::system().name()).toString();
|
m_language = qs->value(QLatin1String("OverrideLanguage"), QLocale::system().name()).toString();
|
||||||
m_saveSettingsOnExit = qs->value(QLatin1String("SaveSettingsOnExit"),m_saveSettingsOnExit).toBool();
|
m_saveSettingsOnExit = qs->value(QLatin1String("SaveSettingsOnExit"), m_saveSettingsOnExit).toBool();
|
||||||
m_autoConnect = qs->value(QLatin1String("AutoConnect"),m_autoConnect).toBool();
|
m_autoConnect = qs->value(QLatin1String("AutoConnect"), m_autoConnect).toBool();
|
||||||
m_autoSelect = qs->value(QLatin1String("AutoSelect"),m_autoSelect).toBool();
|
m_autoSelect = qs->value(QLatin1String("AutoSelect"), m_autoSelect).toBool();
|
||||||
m_useUDPMirror = qs->value(QLatin1String("UDPMirror"),m_useUDPMirror).toBool();
|
m_useUDPMirror = qs->value(QLatin1String("UDPMirror"), m_useUDPMirror).toBool();
|
||||||
m_useExpertMode = qs->value(QLatin1String("ExpertMode"),m_useExpertMode).toBool();
|
m_useExpertMode = qs->value(QLatin1String("ExpertMode"), m_useExpertMode).toBool();
|
||||||
qs->endGroup();
|
qs->endGroup();
|
||||||
}
|
}
|
||||||
|
|
||||||
void GeneralSettings::saveSettings(QSettings* qs)
|
void GeneralSettings::saveSettings(QSettings *qs)
|
||||||
{
|
{
|
||||||
qs->beginGroup(QLatin1String("General"));
|
qs->beginGroup(QLatin1String("General"));
|
||||||
|
|
||||||
if (m_language.isEmpty())
|
if (m_language.isEmpty()) {
|
||||||
qs->remove(QLatin1String("OverrideLanguage"));
|
qs->remove(QLatin1String("OverrideLanguage"));
|
||||||
else
|
}
|
||||||
|
else {
|
||||||
qs->setValue(QLatin1String("OverrideLanguage"), m_language);
|
qs->setValue(QLatin1String("OverrideLanguage"), m_language);
|
||||||
|
}
|
||||||
|
|
||||||
qs->setValue(QLatin1String("SaveSettingsOnExit"), m_saveSettingsOnExit);
|
qs->setValue(QLatin1String("SaveSettingsOnExit"), m_saveSettingsOnExit);
|
||||||
qs->setValue(QLatin1String("AutoConnect"), m_autoConnect);
|
qs->setValue(QLatin1String("AutoConnect"), m_autoConnect);
|
||||||
@ -217,8 +221,8 @@ void GeneralSettings::setLanguage(const QString &locale)
|
|||||||
{
|
{
|
||||||
if (m_language != locale) {
|
if (m_language != locale) {
|
||||||
if (!locale.isEmpty()) {
|
if (!locale.isEmpty()) {
|
||||||
QMessageBox::information((QWidget*)Core::ICore::instance()->mainWindow(), tr("Restart required"),
|
QMessageBox::information((QWidget*) Core::ICore::instance()->mainWindow(), tr("Restart required"),
|
||||||
tr("The language change will take effect after a restart of the OpenPilot GCS."));
|
tr("The language change will take effect after a restart of the OpenPilot GCS."));
|
||||||
}
|
}
|
||||||
m_language = locale;
|
m_language = locale;
|
||||||
}
|
}
|
||||||
@ -251,8 +255,10 @@ bool GeneralSettings::useExpertMode() const
|
|||||||
|
|
||||||
void GeneralSettings::slotAutoConnect(int value)
|
void GeneralSettings::slotAutoConnect(int value)
|
||||||
{
|
{
|
||||||
if (value==Qt::Checked)
|
if (value==Qt::Checked) {
|
||||||
m_page->checkAutoSelect->setEnabled(false);
|
m_page->checkAutoSelect->setEnabled(false);
|
||||||
else
|
}
|
||||||
|
else {
|
||||||
m_page->checkAutoSelect->setEnabled(true);
|
m_page->checkAutoSelect->setEnabled(true);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
@ -85,6 +85,7 @@ private:
|
|||||||
QList<QTextCodec *> m_codecs;
|
QList<QTextCodec *> m_codecs;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace Internal
|
} // namespace Internal
|
||||||
} // namespace Core
|
} // namespace Core
|
||||||
|
|
||||||
|
@ -85,14 +85,12 @@
|
|||||||
#include <QtGui/QMessageBox>
|
#include <QtGui/QMessageBox>
|
||||||
#include <QDesktopServices>
|
#include <QDesktopServices>
|
||||||
#include <QElapsedTimer>
|
#include <QElapsedTimer>
|
||||||
#include "dialogs/importsettings.h"
|
|
||||||
#include <QDir>
|
#include <QDir>
|
||||||
|
|
||||||
using namespace Core;
|
using namespace Core;
|
||||||
using namespace Core::Internal;
|
using namespace Core::Internal;
|
||||||
|
|
||||||
static const char *uriListMimeFormatC = "text/uri-list";
|
static const char *uriListMimeFormatC = "text/uri-list";
|
||||||
static const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml";
|
|
||||||
|
|
||||||
enum { debugMainWindow = 0 };
|
enum { debugMainWindow = 0 };
|
||||||
|
|
||||||
@ -269,66 +267,9 @@ void MainWindow::modeChanged(Core::IMode */*mode*/)
|
|||||||
void MainWindow::extensionsInitialized()
|
void MainWindow::extensionsInitialized()
|
||||||
{
|
{
|
||||||
QSettings *qs = m_settings;
|
QSettings *qs = m_settings;
|
||||||
if (!qs->allKeys().count()) {
|
|
||||||
// no user settings, so try to load some default ones
|
|
||||||
QDir directory(QCoreApplication::applicationDirPath());
|
|
||||||
#ifdef Q_OS_MAC
|
|
||||||
directory.cdUp();
|
|
||||||
directory.cd("Resources");
|
|
||||||
#else
|
|
||||||
directory.cdUp();
|
|
||||||
directory.cd("share");
|
|
||||||
directory.cd("openpilotgcs");
|
|
||||||
#endif
|
|
||||||
directory.cd("default_configurations");
|
|
||||||
|
|
||||||
qDebug() << "Looking for configuration files in:" << directory.absolutePath();
|
|
||||||
|
|
||||||
QString filename;
|
|
||||||
// check if command line contains a config file name
|
|
||||||
QString commandLine;
|
|
||||||
foreach(QString str, qApp->arguments()) {
|
|
||||||
if (str.contains("configfile")) {
|
|
||||||
commandLine = str.split("=").at(1);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (!commandLine.isEmpty() && QFile::exists(directory.absolutePath() + QDir::separator() + commandLine)) {
|
|
||||||
// use file name specified on command line
|
|
||||||
filename = directory.absolutePath() + QDir::separator() + commandLine;
|
|
||||||
qDebug() << "Configuration file" << filename << "specified on command line will be loaded.";
|
|
||||||
} else if (QFile::exists(directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME)) {
|
|
||||||
// use default file name
|
|
||||||
filename = directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME;
|
|
||||||
qDebug() << "Default configuration file" << filename << "will be loaded.";
|
|
||||||
} else {
|
|
||||||
// prompt user for default file name
|
|
||||||
qDebug() << "Default configuration file" << directory.absolutePath() << QDir::separator()
|
|
||||||
<< DEFAULT_CONFIG_FILENAME << "was not found.";
|
|
||||||
importSettings *dialog = new importSettings(this);
|
|
||||||
dialog->loadFiles(directory.absolutePath());
|
|
||||||
dialog->exec();
|
|
||||||
filename = dialog->choosenConfig();
|
|
||||||
delete dialog;
|
|
||||||
qDebug() << "Configuration file" << filename << "was selected and will be loaded.";
|
|
||||||
}
|
|
||||||
|
|
||||||
// create settings from file
|
|
||||||
qs = new QSettings(filename, XmlConfig::XmlSettingsFormat);
|
|
||||||
|
|
||||||
// transfer loaded settings to application settings
|
|
||||||
QStringList keys = qs->allKeys();
|
|
||||||
foreach(QString key, keys) {
|
|
||||||
m_settings->setValue(key, qs->value(key));
|
|
||||||
}
|
|
||||||
|
|
||||||
// and delete loaded settings
|
|
||||||
delete qs;
|
|
||||||
qs = m_settings;
|
|
||||||
|
|
||||||
qDebug() << "Configuration file" << filename << "was loaded.";
|
|
||||||
}
|
|
||||||
|
|
||||||
qs->beginGroup("General");
|
qs->beginGroup("General");
|
||||||
|
|
||||||
m_config_description = qs->value("Description", "none").toString();
|
m_config_description = qs->value("Description", "none").toString();
|
||||||
m_config_details = qs->value("Details", "none").toString();
|
m_config_details = qs->value("Details", "none").toString();
|
||||||
m_config_stylesheet = qs->value("StyleSheet", "none").toString();
|
m_config_stylesheet = qs->value("StyleSheet", "none").toString();
|
||||||
|
@ -39,72 +39,74 @@
|
|||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
import QtQuick 1.1
|
import QtQuick 1.1
|
||||||
import QtWebKit 1.0
|
|
||||||
|
|
||||||
// This is a tabbed pane element. Add a nested Rectangle to add a tab.
|
// This is a tabbed pane element. Add a nested Rectangle to add a tab.
|
||||||
TabWidget {
|
TabWidget {
|
||||||
id: tabs
|
// Define AuthorsModel as type
|
||||||
width: 640; height: 480
|
property AuthorsModel authors: AuthorsModel {}
|
||||||
// This tab is for the GCS version information
|
|
||||||
Rectangle {
|
id: tabs
|
||||||
property string title: "OpenPilot GCS"
|
width: 640; height: 480
|
||||||
anchors.fill: parent
|
// This tab is for the GCS version information
|
||||||
color: "#e3e3e3"
|
Rectangle {
|
||||||
|
property string title: "OpenPilot GCS"
|
||||||
Rectangle {
|
anchors.fill: parent
|
||||||
anchors.fill: parent; anchors.margins: 20
|
color: "#e3e3e3"
|
||||||
color: "#e3e3e3"
|
|
||||||
Image {
|
Rectangle {
|
||||||
source: "../images/openpilot_logo_128.png"
|
anchors.fill: parent; anchors.margins: 20
|
||||||
x: 0; y: 0; z: 100
|
color: "#e3e3e3"
|
||||||
fillMode: Image.PreserveAspectFit
|
Image {
|
||||||
}
|
source: "../images/openpilot_logo_128.png"
|
||||||
Flickable {
|
x: 0; y: 0; z: 100
|
||||||
anchors.fill: parent
|
fillMode: Image.PreserveAspectFit
|
||||||
anchors.centerIn: parent
|
}
|
||||||
Text {
|
Flickable {
|
||||||
id: versionLabel
|
anchors.fill: parent
|
||||||
x: 156; y: 0
|
anchors.centerIn: parent
|
||||||
width: 430; height: 379
|
Text {
|
||||||
horizontalAlignment: Qt.AlignLeft
|
id: versionLabel
|
||||||
font.pixelSize: 12
|
x: 156; y: 0
|
||||||
wrapMode: Text.WordWrap
|
width: 430; height: 379
|
||||||
// @var version exposed in authorsdialog.cpp
|
horizontalAlignment: Qt.AlignLeft
|
||||||
text: version
|
font.pixelSize: 12
|
||||||
}
|
wrapMode: Text.WordWrap
|
||||||
}
|
// @var version exposed in authorsdialog.cpp
|
||||||
|
text: version
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// This is a stub for the Plugins.
|
}
|
||||||
// Rectangle {
|
|
||||||
// property string title: "Plugins"
|
// This tab is for the authors/contributors/credits
|
||||||
// anchors.fill: parent
|
Rectangle {
|
||||||
// color: "#e3e3e3"
|
property string title: "Authors"
|
||||||
//
|
anchors.fill: parent; color: "#e3e3e3"
|
||||||
// Rectangle {
|
|
||||||
// anchors.fill: parent; anchors.margins: 20
|
|
||||||
// color: "#7fff7f"
|
|
||||||
// Text {
|
|
||||||
// width: parent.width - 20
|
|
||||||
// anchors.centerIn: parent; horizontalAlignment: Qt.AlignHCenter
|
|
||||||
// font.pixelSize: 20
|
|
||||||
// wrapMode: Text.WordWrap
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
// This tab is for the authors/contributors/credits
|
|
||||||
Rectangle {
|
Rectangle {
|
||||||
property string title: "Authors"
|
anchors.fill: parent; anchors.margins: 20
|
||||||
anchors.fill: parent; color: "#e3e3e3"
|
color: "#e3e3e3"
|
||||||
Rectangle {
|
Text {
|
||||||
anchors.fill: parent; anchors.margins: 20
|
id: description
|
||||||
color: "#e3e3e3"
|
text: "<h4>These people have been key contributors to the OpenPilot project. Without the work of the people in this list, OpenPilot would not be what it is today.</h4><p>This list is sorted alphabetically by name</p>"
|
||||||
FlickableWebView {
|
width: 600
|
||||||
id: webView
|
wrapMode: Text.WordWrap
|
||||||
z: 0
|
|
||||||
url: "../CREDITS.html"
|
}
|
||||||
anchors { top: parent.top; left: parent.left; right: parent.right; bottom: parent.bottom }
|
ListView {
|
||||||
}
|
id: authorsView
|
||||||
}
|
y: description.y + description.height + 20
|
||||||
}
|
width: parent.width; height: parent.height - description.height - 20
|
||||||
}
|
spacing: 3
|
||||||
|
model: authors
|
||||||
|
delegate: Text {
|
||||||
|
text: name
|
||||||
|
}
|
||||||
|
clip: true
|
||||||
|
}
|
||||||
|
ScrollDecorator {
|
||||||
|
flickableItem: authorsView
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
151
ground/openpilotgcs/src/plugins/coreplugin/qml/AuthorsModel.qml
Normal file
151
ground/openpilotgcs/src/plugins/coreplugin/qml/AuthorsModel.qml
Normal file
@ -0,0 +1,151 @@
|
|||||||
|
/*
|
||||||
|
This list model was created for the AuthorsDialog.
|
||||||
|
*/
|
||||||
|
import QtQuick 1.1
|
||||||
|
|
||||||
|
ListModel {
|
||||||
|
|
||||||
|
ListElement{ name:"Connor Abbott" }
|
||||||
|
|
||||||
|
ListElement{ name:"David Ankers" }
|
||||||
|
|
||||||
|
ListElement{ name:"Sergiy Anikeyev" }
|
||||||
|
|
||||||
|
ListElement{ name:"Pedro Assuncao" }
|
||||||
|
|
||||||
|
ListElement{ name:"Fredrik Arvidsson" }
|
||||||
|
|
||||||
|
ListElement{ name:"Werner Backes" }
|
||||||
|
|
||||||
|
ListElement{ name:"Jose Barros" }
|
||||||
|
|
||||||
|
ListElement{ name:"Pete Boehl" }
|
||||||
|
|
||||||
|
ListElement{ name:"David Carlson" }
|
||||||
|
|
||||||
|
ListElement{ name:"James Cotton" }
|
||||||
|
|
||||||
|
ListElement{ name:"Steve Doll" }
|
||||||
|
|
||||||
|
ListElement{ name:"Piotr Esden-Tempski" }
|
||||||
|
|
||||||
|
ListElement{ name:"Richard Flay" }
|
||||||
|
|
||||||
|
ListElement{ name:"Peter Farnworth" }
|
||||||
|
|
||||||
|
ListElement{ name:"Ed Faulkner" }
|
||||||
|
|
||||||
|
ListElement{ name:"Darren Furniss" }
|
||||||
|
|
||||||
|
ListElement{ name:"Frederic Goddeeris" }
|
||||||
|
|
||||||
|
ListElement{ name:"Daniel Godin" }
|
||||||
|
|
||||||
|
ListElement{ name:"Bani Greyling" }
|
||||||
|
|
||||||
|
ListElement{ name:"Nuno Guedes" }
|
||||||
|
|
||||||
|
ListElement{ name:"Erik Gustavsson" }
|
||||||
|
|
||||||
|
ListElement{ name:"Peter Gunnarsson" }
|
||||||
|
|
||||||
|
ListElement{ name:"Dean Hall" }
|
||||||
|
|
||||||
|
ListElement{ name:"Joe Hlebasko" }
|
||||||
|
|
||||||
|
ListElement{ name:"Andy Honecker" }
|
||||||
|
|
||||||
|
ListElement{ name:"Ryan Hunt" }
|
||||||
|
|
||||||
|
ListElement{ name:"Mark James" }
|
||||||
|
|
||||||
|
ListElement{ name:"Sami Korhonen" }
|
||||||
|
|
||||||
|
ListElement{ name:"Thorsten Klose" }
|
||||||
|
|
||||||
|
ListElement{ name:"Hallvard Kristiansen" }
|
||||||
|
|
||||||
|
ListElement{ name:"Edouard Lafargue" }
|
||||||
|
|
||||||
|
ListElement{ name:"Mike Labranche" }
|
||||||
|
|
||||||
|
ListElement{ name:"Fredrik Larsson" }
|
||||||
|
|
||||||
|
ListElement{ name:"Pablo Lema" }
|
||||||
|
|
||||||
|
ListElement{ name:"David Llama" }
|
||||||
|
|
||||||
|
ListElement{ name:"Matt Lipski" }
|
||||||
|
|
||||||
|
ListElement{ name:"Les Newell" }
|
||||||
|
|
||||||
|
ListElement{ name:"Ken Northup" }
|
||||||
|
|
||||||
|
ListElement{ name:"Greg Matthews" }
|
||||||
|
|
||||||
|
ListElement{ name:"Guy McCaldin" }
|
||||||
|
|
||||||
|
ListElement{ name:"Gary Mortimer" }
|
||||||
|
|
||||||
|
ListElement{ name:"Alessio Morale" }
|
||||||
|
|
||||||
|
ListElement{ name:"Cathy Moss" }
|
||||||
|
|
||||||
|
ListElement{ name:"Angus Peart" }
|
||||||
|
|
||||||
|
ListElement{ name:"Dmytro Poplavskiy" }
|
||||||
|
|
||||||
|
ListElement{ name:"Eric Price" }
|
||||||
|
|
||||||
|
ListElement{ name:"Richard Querin" }
|
||||||
|
|
||||||
|
ListElement{ name:"Randy Ram" }
|
||||||
|
|
||||||
|
ListElement{ name:"Laurent Ribon" }
|
||||||
|
|
||||||
|
ListElement{ name:"Julien Rouviere" }
|
||||||
|
|
||||||
|
ListElement{ name:"Jackson Russell" }
|
||||||
|
|
||||||
|
ListElement{ name:"Zik Saleeba" }
|
||||||
|
|
||||||
|
ListElement{ name:"Professor Dale Schinstock" }
|
||||||
|
|
||||||
|
ListElement{ name:"Professor Kenn Sebesta" }
|
||||||
|
|
||||||
|
ListElement{ name:"Oleg Semyonov" }
|
||||||
|
|
||||||
|
ListElement{ name:"Stacey Sheldon" }
|
||||||
|
|
||||||
|
ListElement{ name:"Troy Schultz" }
|
||||||
|
|
||||||
|
ListElement{ name:"Dr. Erhard Siegl" }
|
||||||
|
|
||||||
|
ListElement{ name:"Mike Smith" }
|
||||||
|
|
||||||
|
ListElement{ name:"Alex Sowa" }
|
||||||
|
|
||||||
|
ListElement{ name:"Pete Stapley" }
|
||||||
|
|
||||||
|
ListElement{ name:"Rowan Taubitz" }
|
||||||
|
|
||||||
|
ListElement{ name:"Andrew Thoms" }
|
||||||
|
|
||||||
|
ListElement{ name:"Jasper van Loenen" }
|
||||||
|
|
||||||
|
ListElement{ name:"Vassilis Varveropoulos" }
|
||||||
|
|
||||||
|
ListElement{ name:"Kevin Vertucio" }
|
||||||
|
|
||||||
|
ListElement{ name:"Alex Vrubel" }
|
||||||
|
|
||||||
|
ListElement{ name:"Brian Webb" }
|
||||||
|
|
||||||
|
ListElement{ name:"Justin Welander" }
|
||||||
|
|
||||||
|
ListElement{ name:"Mat Wellington" }
|
||||||
|
|
||||||
|
ListElement{ name:"Kendal Wells" }
|
||||||
|
|
||||||
|
ListElement{ name:"Dmitriy Zaitsev" }
|
||||||
|
}
|
@ -1,196 +0,0 @@
|
|||||||
/****************************************************************************
|
|
||||||
**
|
|
||||||
** Copyright (C) 2012 Nokia Corporation and/or its subsidiary(-ies).
|
|
||||||
** Contact: http://www.qt-project.org/
|
|
||||||
**
|
|
||||||
** This file is part of the QtDeclarative module of the Qt Toolkit.
|
|
||||||
**
|
|
||||||
** $QT_BEGIN_LICENSE:LGPL$
|
|
||||||
** GNU Lesser General Public License Usage
|
|
||||||
** This file may be used under the terms of the GNU Lesser General Public
|
|
||||||
** License version 2.1 as published by the Free Software Foundation and
|
|
||||||
** appearing in the file LICENSE.LGPL included in the packaging of this
|
|
||||||
** file. Please review the following information to ensure the GNU Lesser
|
|
||||||
** General Public License version 2.1 requirements will be met:
|
|
||||||
** http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html.
|
|
||||||
**
|
|
||||||
** In addition, as a special exception, Nokia gives you certain additional
|
|
||||||
** rights. These rights are described in the Nokia Qt LGPL Exception
|
|
||||||
** version 1.1, included in the file LGPL_EXCEPTION.txt in this package.
|
|
||||||
**
|
|
||||||
** GNU General Public License Usage
|
|
||||||
** Alternatively, this file may be used under the terms of the GNU General
|
|
||||||
** Public License version 3.0 as published by the Free Software Foundation
|
|
||||||
** and appearing in the file LICENSE.GPL included in the packaging of this
|
|
||||||
** file. Please review the following information to ensure the GNU General
|
|
||||||
** Public License version 3.0 requirements will be met:
|
|
||||||
** http://www.gnu.org/copyleft/gpl.html.
|
|
||||||
**
|
|
||||||
** Other Usage
|
|
||||||
** Alternatively, this file may be used in accordance with the terms and
|
|
||||||
** conditions contained in a signed written agreement between you and Nokia.
|
|
||||||
**
|
|
||||||
**
|
|
||||||
**
|
|
||||||
**
|
|
||||||
**
|
|
||||||
**
|
|
||||||
** $QT_END_LICENSE$
|
|
||||||
**
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
import QtQuick 1.0
|
|
||||||
import QtWebKit 1.0
|
|
||||||
|
|
||||||
Flickable {
|
|
||||||
property alias title: webView.title
|
|
||||||
property alias icon: webView.icon
|
|
||||||
property alias progress: webView.progress
|
|
||||||
property alias url: webView.url
|
|
||||||
property alias back: webView.back
|
|
||||||
property alias stop: webView.stop
|
|
||||||
property alias reload: webView.reload
|
|
||||||
property alias forward: webView.forward
|
|
||||||
|
|
||||||
id: flickable
|
|
||||||
width: parent.width
|
|
||||||
contentWidth: Math.max(parent.width,webView.width)
|
|
||||||
contentHeight: Math.max(parent.height,webView.height)
|
|
||||||
// anchors.top: headerSpace.bottom
|
|
||||||
anchors.bottom: parent.top
|
|
||||||
anchors.left: parent.left
|
|
||||||
anchors.right: parent.right
|
|
||||||
pressDelay: 200
|
|
||||||
clip: true
|
|
||||||
|
|
||||||
onWidthChanged : {
|
|
||||||
// Expand (but not above 1:1) if otherwise would be smaller that available width.
|
|
||||||
if (width > webView.width*webView.contentsScale && webView.contentsScale < 1.0)
|
|
||||||
webView.contentsScale = width / webView.width * webView.contentsScale;
|
|
||||||
}
|
|
||||||
|
|
||||||
WebView {
|
|
||||||
id: webView
|
|
||||||
transformOrigin: Item.TopLeft
|
|
||||||
|
|
||||||
function fixUrl(url)
|
|
||||||
{
|
|
||||||
if (url == "") return url
|
|
||||||
if (url[0] == "/") return "file://"+url
|
|
||||||
if (url.indexOf(":")<0) {
|
|
||||||
if (url.indexOf(".")<0 || url.indexOf(" ")>=0) {
|
|
||||||
// Fall back to a search engine; hard-code Wikipedia
|
|
||||||
return "http://en.wikipedia.org/w/index.php?search="+url
|
|
||||||
} else {
|
|
||||||
return "http://"+url
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return url
|
|
||||||
}
|
|
||||||
|
|
||||||
url: fixUrl(webBrowser.urlString)
|
|
||||||
smooth: false // We don't want smooth scaling, since we only scale during (fast) transitions
|
|
||||||
focus: true
|
|
||||||
|
|
||||||
onAlert: console.log(message)
|
|
||||||
|
|
||||||
function doZoom(zoom,centerX,centerY)
|
|
||||||
{
|
|
||||||
if (centerX) {
|
|
||||||
var sc = zoom*contentsScale;
|
|
||||||
scaleAnim.to = sc;
|
|
||||||
flickVX.from = flickable.contentX
|
|
||||||
flickVX.to = Math.max(0,Math.min(centerX-flickable.width/2,webView.width*sc-flickable.width))
|
|
||||||
finalX.value = flickVX.to
|
|
||||||
flickVY.from = flickable.contentY
|
|
||||||
flickVY.to = Math.max(0,Math.min(centerY-flickable.height/2,webView.height*sc-flickable.height))
|
|
||||||
finalY.value = flickVY.to
|
|
||||||
quickZoom.start()
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
Keys.onLeftPressed: webView.contentsScale -= 0.1
|
|
||||||
Keys.onRightPressed: webView.contentsScale += 0.1
|
|
||||||
|
|
||||||
preferredWidth: flickable.width
|
|
||||||
preferredHeight: flickable.height
|
|
||||||
contentsScale: 1
|
|
||||||
onContentsSizeChanged: {
|
|
||||||
// zoom out
|
|
||||||
contentsScale = Math.min(1,flickable.width / contentsSize.width)
|
|
||||||
}
|
|
||||||
onUrlChanged: {
|
|
||||||
// got to topleft
|
|
||||||
flickable.contentX = 0
|
|
||||||
flickable.contentY = 0
|
|
||||||
// if (url != null) { header.editUrl = url.toString(); }
|
|
||||||
}
|
|
||||||
onDoubleClick: {
|
|
||||||
if (!heuristicZoom(clickX,clickY,2.5)) {
|
|
||||||
var zf = flickable.width / contentsSize.width
|
|
||||||
if (zf >= contentsScale)
|
|
||||||
zf = 2.0*contentsScale // zoom in (else zooming out)
|
|
||||||
doZoom(zf,clickX*zf,clickY*zf)
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
SequentialAnimation {
|
|
||||||
id: quickZoom
|
|
||||||
|
|
||||||
PropertyAction {
|
|
||||||
target: webView
|
|
||||||
property: "renderingEnabled"
|
|
||||||
value: false
|
|
||||||
}
|
|
||||||
ParallelAnimation {
|
|
||||||
NumberAnimation {
|
|
||||||
id: scaleAnim
|
|
||||||
target: webView
|
|
||||||
property: "contentsScale"
|
|
||||||
// the to property is set before calling
|
|
||||||
easing.type: Easing.Linear
|
|
||||||
duration: 200
|
|
||||||
}
|
|
||||||
NumberAnimation {
|
|
||||||
id: flickVX
|
|
||||||
target: flickable
|
|
||||||
property: "contentX"
|
|
||||||
easing.type: Easing.Linear
|
|
||||||
duration: 200
|
|
||||||
from: 0 // set before calling
|
|
||||||
to: 0 // set before calling
|
|
||||||
}
|
|
||||||
NumberAnimation {
|
|
||||||
id: flickVY
|
|
||||||
target: flickable
|
|
||||||
property: "contentY"
|
|
||||||
easing.type: Easing.Linear
|
|
||||||
duration: 200
|
|
||||||
from: 0 // set before calling
|
|
||||||
to: 0 // set before calling
|
|
||||||
}
|
|
||||||
}
|
|
||||||
// Have to set the contentXY, since the above 2
|
|
||||||
// size changes may have started a correction if
|
|
||||||
// contentsScale < 1.0.
|
|
||||||
PropertyAction {
|
|
||||||
id: finalX
|
|
||||||
target: flickable
|
|
||||||
property: "contentX"
|
|
||||||
value: 0 // set before calling
|
|
||||||
}
|
|
||||||
PropertyAction {
|
|
||||||
id: finalY
|
|
||||||
target: flickable
|
|
||||||
property: "contentY"
|
|
||||||
value: 0 // set before calling
|
|
||||||
}
|
|
||||||
PropertyAction {
|
|
||||||
target: webView
|
|
||||||
property: "renderingEnabled"
|
|
||||||
value: true
|
|
||||||
}
|
|
||||||
}
|
|
||||||
onZoomTo: doZoom(zoom,centerX,centerY)
|
|
||||||
}
|
|
||||||
}
|
|
@ -0,0 +1,40 @@
|
|||||||
|
import QtQuick 1.1
|
||||||
|
|
||||||
|
Rectangle {
|
||||||
|
id: scrollDecorator
|
||||||
|
|
||||||
|
property Flickable flickableItem: null
|
||||||
|
|
||||||
|
Loader {
|
||||||
|
id: scrollLoader
|
||||||
|
sourceComponent: scrollDecorator.flickableItem ? scrollBar : undefined
|
||||||
|
}
|
||||||
|
|
||||||
|
Component.onDestruction: scrollLoader.sourceComponent = undefined
|
||||||
|
|
||||||
|
Component {
|
||||||
|
id: scrollBar
|
||||||
|
Rectangle {
|
||||||
|
property Flickable flickable: scrollDecorator.flickableItem
|
||||||
|
|
||||||
|
parent: flickable
|
||||||
|
anchors.right: parent.right
|
||||||
|
|
||||||
|
smooth: true
|
||||||
|
radius: 2
|
||||||
|
color: "gray"
|
||||||
|
border.color: "lightgray"
|
||||||
|
border.width: 1.0
|
||||||
|
opacity: flickable.moving ? 0.8 : 0.4
|
||||||
|
|
||||||
|
Behavior on opacity {
|
||||||
|
NumberAnimation { duration: 500 }
|
||||||
|
}
|
||||||
|
|
||||||
|
width: 4
|
||||||
|
height: flickable.height * (flickable.height / flickable.contentHeight)
|
||||||
|
y: flickable.height * (flickable.contentY / flickable.contentHeight)
|
||||||
|
visible: flickable.height < flickable.contentHeight
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
@ -101,18 +101,27 @@ void UAVObjectField::constructorInitialize(const QString& name, const QString& u
|
|||||||
|
|
||||||
void UAVObjectField::limitsInitialize(const QString &limits)
|
void UAVObjectField::limitsInitialize(const QString &limits)
|
||||||
{
|
{
|
||||||
/// format
|
// Limit string format:
|
||||||
/// (TY)->type (EQ-equal;NE-not equal;BE-between;BI-bigger;SM-smaller)
|
// % - start char
|
||||||
/// (VALX)->value
|
// XXXX - optional BOARD_TYPE and BOARD_REVISION (4 hex digits)
|
||||||
/// %TY:VAL1:VAL2:VAL3,%TY,VAL1,VAL2,VAL3
|
// TY - rule type (EQ-equal, NE-not equal, BE-between, BI-bigger, SM-smaller)
|
||||||
/// example: first element bigger than 3 and second element inside [2.3,5]
|
// VAL - values for TY separated by colon
|
||||||
/// "%BI:3,%BE:2.3:5"
|
// , - rule separator (may have leading or trailing spaces)
|
||||||
|
// ; - element separator (may have leading or trailing spaces)
|
||||||
|
//
|
||||||
|
// Examples:
|
||||||
|
// Disable few flight modes for Revo (00903):
|
||||||
|
// "%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner"
|
||||||
|
// Original CC board (rev 1), first element bigger than 3 and second element inside [2.3-5.0]:
|
||||||
|
// "%0401BI:3; %BE:2.3:5"
|
||||||
|
// Set applicable range [0-500] for 3 elements of array for all boards:
|
||||||
|
// "%BE:0:500; %BE:0:500; %BE:0:500"
|
||||||
if(limits.isEmpty())
|
if(limits.isEmpty())
|
||||||
return;
|
return;
|
||||||
QStringList stringPerElement=limits.split(",");
|
QStringList stringPerElement = limits.split(";");
|
||||||
quint32 index=0;
|
quint32 index=0;
|
||||||
foreach (QString str, stringPerElement) {
|
foreach (QString str, stringPerElement) {
|
||||||
QStringList ruleList=str.split(";");
|
QStringList ruleList = str.split(",");
|
||||||
QList<LimitStruct> limitList;
|
QList<LimitStruct> limitList;
|
||||||
foreach(QString rule,ruleList)
|
foreach(QString rule,ruleList)
|
||||||
{
|
{
|
||||||
|
@ -101,8 +101,8 @@ SRC += $(MATHLIB)/sin_lookup.c
|
|||||||
SRC += $(MATHLIB)/pid.c
|
SRC += $(MATHLIB)/pid.c
|
||||||
|
|
||||||
## Modules
|
## Modules
|
||||||
SRC += $(foreach mod, $(MODULES), $(wildcard $(OPMODULEDIR)/$(mod)/*.c))
|
SRC += $(foreach mod, $(MODULES), $(sort $(wildcard $(OPMODULEDIR)/$(mod)/*.c)))
|
||||||
SRC += $(foreach mod, $(OPTMODULES), $(wildcard $(OPMODULEDIR)/$(mod)/*.c))
|
SRC += $(foreach mod, $(OPTMODULES), $(sort $(wildcard $(OPMODULEDIR)/$(mod)/*.c)))
|
||||||
|
|
||||||
# Declare all non-optional modules as built-in to force inclusion.
|
# Declare all non-optional modules as built-in to force inclusion.
|
||||||
# Built-in modules are always enabled and cannot be disabled.
|
# Built-in modules are always enabled and cannot be disabled.
|
||||||
@ -175,3 +175,6 @@ ifeq ($(MCU),cortex-m3)
|
|||||||
else ifeq ($(MCU),cortex-m4)
|
else ifeq ($(MCU),cortex-m4)
|
||||||
LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP))
|
LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP))
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
# Add jtag targets (program and wipe)
|
||||||
|
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG)))
|
||||||
|
@ -126,3 +126,6 @@ ifeq ($(MCU),cortex-m3)
|
|||||||
else ifeq ($(MCU),cortex-m4)
|
else ifeq ($(MCU),cortex-m4)
|
||||||
LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_BL))
|
LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_BL))
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
# Add jtag targets (program and wipe)
|
||||||
|
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG)))
|
||||||
|
@ -223,13 +223,10 @@ $(eval $(call PARTIAL_COMPILE_TEMPLATE, SRC))
|
|||||||
# Compile: create assembler files from C source files. ARM only
|
# Compile: create assembler files from C source files. ARM only
|
||||||
$(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM))
|
$(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM))
|
||||||
|
|
||||||
$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin
|
|
||||||
|
|
||||||
# Add opfw target
|
# Add opfw target
|
||||||
$(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION)))
|
$(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION)))
|
||||||
|
|
||||||
# Add jtag targets (program and wipe)
|
$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin
|
||||||
$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG)))
|
|
||||||
|
|
||||||
.PHONY: elf lss sym hex bin bino opfw
|
.PHONY: elf lss sym hex bin bino opfw
|
||||||
elf: $(OUTDIR)/$(TARGET).elf
|
elf: $(OUTDIR)/$(TARGET).elf
|
||||||
|
@ -52,15 +52,16 @@ endif
|
|||||||
##############################
|
##############################
|
||||||
|
|
||||||
ifeq ($(UNAME), Linux)
|
ifeq ($(UNAME), Linux)
|
||||||
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux.tar.bz2
|
|
||||||
ifeq ($(ARCH), x86_64)
|
ifeq ($(ARCH), x86_64)
|
||||||
QT_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-4.8.4-linux-x64.tar.bz2
|
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux-amd64.tar.bz2
|
||||||
|
QT_SDK_URL := "Please install native Qt 4.8.x SDK using package manager"
|
||||||
else
|
else
|
||||||
QT_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-4.8.4-linux.tar.bz2
|
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-linux-i686.tar.bz2
|
||||||
|
QT_SDK_URL := "Please install native Qt 4.8.x SDK using package manager"
|
||||||
endif
|
endif
|
||||||
else ifeq ($(UNAME), Darwin)
|
else ifeq ($(UNAME), Darwin)
|
||||||
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-mac.tar.bz2
|
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-mac.tar.bz2
|
||||||
QT_SDK_URL := TODO/qt-4.8.4-mac.tar.bz2
|
QT_SDK_URL := "Please install native Qt 4.8.x SDK using package manager"
|
||||||
else ifeq ($(UNAME), Windows)
|
else ifeq ($(UNAME), Windows)
|
||||||
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-windows.tar.bz2
|
ARM_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/gcc-arm-none-eabi-4_7-2013q1-20130313-windows.tar.bz2
|
||||||
QT_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-4.8.4-windows.tar.bz2
|
QT_SDK_URL := http://wiki.openpilot.org/download/attachments/18612236/qt-4.8.4-windows.tar.bz2
|
||||||
|
@ -20,7 +20,7 @@ set -e
|
|||||||
|
|
||||||
case "$1" in
|
case "$1" in
|
||||||
configure)
|
configure)
|
||||||
sudo udevadm control --reload-rules >&2
|
/sbin/udevadm control --reload-rules >&2
|
||||||
;;
|
;;
|
||||||
|
|
||||||
abort-upgrade|abort-remove|abort-deconfigure)
|
abort-upgrade|abort-remove|abort-deconfigure)
|
||||||
|
@ -20,13 +20,55 @@
|
|||||||
<field name="Arming" units="" type="enum" elements="1" options="Always Disarmed,Always Armed,Roll Left,Roll Right,Pitch Forward,Pitch Aft,Yaw Left,Yaw Right" defaultvalue="Always Disarmed"/>
|
<field name="Arming" units="" type="enum" elements="1" options="Always Disarmed,Always Armed,Roll Left,Roll Right,Pitch Forward,Pitch Aft,Yaw Left,Yaw Right" defaultvalue="Always Disarmed"/>
|
||||||
|
|
||||||
<!-- Note these options should be identical to those in StabilizationDesired.StabilizationMode -->
|
<!-- Note these options should be identical to those in StabilizationDesired.StabilizationMode -->
|
||||||
<field name="Stabilization1Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,RelayRate,RelayAttitude" defaultvalue="Attitude,Attitude,Rate"/>
|
<field name="Stabilization1Settings" units="" type="enum"
|
||||||
<field name="Stabilization2Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,RelayRate,RelayAttitude" defaultvalue="Attitude,Attitude,Rate"/>
|
elementnames="Roll,Pitch,Yaw"
|
||||||
<field name="Stabilization3Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,RelayRate,RelayAttitude" defaultvalue="Attitude,Attitude,Rate"/>
|
options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,RelayRate,RelayAttitude"
|
||||||
|
defaultvalue="Attitude,Attitude,Rate"
|
||||||
|
limits="%NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude;"/>
|
||||||
|
<field name="Stabilization2Settings" units="" type="enum"
|
||||||
|
elementnames="Roll,Pitch,Yaw"
|
||||||
|
options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,RelayRate,RelayAttitude"
|
||||||
|
defaultvalue="Attitude,Attitude,Rate"
|
||||||
|
limits="%NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude;"/>
|
||||||
|
<field name="Stabilization3Settings" units="" type="enum"
|
||||||
|
elementnames="Roll,Pitch,Yaw"
|
||||||
|
options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,RelayRate,RelayAttitude"
|
||||||
|
defaultvalue="Attitude,Attitude,Rate"
|
||||||
|
limits="%NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude; %NE:RelayRate:RelayAttitude;"/>
|
||||||
|
|
||||||
<!-- Note these options values should be identical to those defined in FlightMode -->
|
<!-- Note these options values should be identical to those defined in FlightMode -->
|
||||||
<field name="FlightModeNumber" units="" type="uint8" elements="1" defaultvalue="3"/>
|
<field name="FlightModeNumber" units="" type="uint8" elements="1" defaultvalue="3"/>
|
||||||
<field name="FlightModePosition" units="" type="enum" elements="6" options="Manual,Stabilized1,Stabilized2,Stabilized3,Autotune,AltitudeHold,VelocityControl,PositionHold,ReturnToBase,Land,PathPlanner" defaultvalue="Manual,Stabilized1,Stabilized2,Stabilized3,AltitudeHold,PositionHold" limits="%0401NE:AltitudeHold:VelocityControl:PositionHold:Autotune;%0402NE:AltitudeHold:VelocityControl:PositionHold:Autotune,%0401NE:AltitudeHold:VelocityControl:PositionHold:Autotune;%0402NE:AltitudeHold:VelocityControl:PositionHold:Autotune,%0401NE:AltitudeHold:VelocityControl:PositionHold:Autotune;%0402NE:AltitudeHold:VelocityControl:PositionHold:Autotune,%0401NE:AltitudeHold:VelocityControl:PositionHold:Autotune;%0402NE:AltitudeHold:VelocityControl:PositionHold:Autotune,%0401NE:AltitudeHold:VelocityControl:PositionHold:Autotune;%0402NE:AltitudeHold:VelocityControl:PositionHold:Autotune,%0401NE:AltitudeHold:VelocityControl:PositionHold:Autotune;%0402NE:AltitudeHold:VelocityControl:PositionHold:Autotune"/>
|
<!-- Currently only some modes are enabled for UI using limits attribute per board. Update when more modes will be operational -->
|
||||||
|
<field name="FlightModePosition"
|
||||||
|
units=""
|
||||||
|
type="enum"
|
||||||
|
elements="6"
|
||||||
|
options="Manual,Stabilized1,Stabilized2,Stabilized3,Autotune,AltitudeHold,VelocityControl,PositionHold,ReturnToBase,Land,PathPlanner"
|
||||||
|
defaultvalue="Manual,Stabilized1,Stabilized2,Stabilized3,AltitudeHold,PositionHold"
|
||||||
|
limits="\
|
||||||
|
%0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner;\
|
||||||
|
\
|
||||||
|
%0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner;\
|
||||||
|
\
|
||||||
|
%0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner;\
|
||||||
|
\
|
||||||
|
%0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner;\
|
||||||
|
\
|
||||||
|
%0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner;\
|
||||||
|
\
|
||||||
|
%0401NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0402NE:Autotune:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner,\
|
||||||
|
%0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner"/>
|
||||||
|
|
||||||
<field name="ArmedTimeout" units="ms" type="uint16" elements="1" defaultvalue="30000"/>
|
<field name="ArmedTimeout" units="ms" type="uint16" elements="1" defaultvalue="30000"/>
|
||||||
<field name="FailsafeBehavior" units="" type="enum" elements="1" options="None" defaultvalue="None"/>
|
<field name="FailsafeBehavior" units="" type="enum" elements="1" options="None" defaultvalue="None"/>
|
||||||
|
@ -4,15 +4,15 @@
|
|||||||
<field name="RollMax" units="degrees" type="uint8" elements="1" defaultvalue="60" limits="%BE:0:180"/>
|
<field name="RollMax" units="degrees" type="uint8" elements="1" defaultvalue="60" limits="%BE:0:180"/>
|
||||||
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="60" limits="%BE:0:180"/>
|
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="60" limits="%BE:0:180"/>
|
||||||
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="60" limits="%BE:0:180"/>
|
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="60" limits="%BE:0:180"/>
|
||||||
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="200,200,200" limits="%BE:0:500,%BE:0:500,%BE:0:500"/>
|
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="200,200,200" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||||
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300" limits="%BE:0:500,%BE:0:500,%BE:0:500"/>
|
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300" limits="%BE:0:500; %BE:0:500; %BE:0:500"/>
|
||||||
|
|
||||||
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01,%BE:0:0.01,, "/>
|
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||||
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01,%BE:0:0.01,, "/>
|
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.003,0.003,0.00002,0.3" limits="%BE:0:0.01; %BE:0:0.01; ; "/>
|
||||||
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3" limits="%BE:0:0.01,%BE:0:0.01,, "/>
|
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3" limits="%BE:0:0.01; %BE:0:0.01 ; ; "/>
|
||||||
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10,%BE:0:10,"/>
|
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||||
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10,%BE:0:10,"/>
|
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2.5,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||||
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50" limits="%BE:0:10,%BE:0:10,"/>
|
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50" limits="%BE:0:10; %BE:0:10; "/>
|
||||||
|
|
||||||
<field name="VbarSensitivity" units="frac" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="0.5,0.5,0.5"/>
|
<field name="VbarSensitivity" units="frac" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="0.5,0.5,0.5"/>
|
||||||
<field name="VbarRollPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
|
<field name="VbarRollPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
|
||||||
|
@ -1,12 +1,13 @@
|
|||||||
<xml>
|
<xml>
|
||||||
<object name="SystemAlarms" singleinstance="true" settings="false">
|
<object name="SystemAlarms" singleinstance="true" settings="false">
|
||||||
<description>Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules.</description>
|
<description>Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. Some modules may have a module defined Status and Substatus fields that details its condition.</description>
|
||||||
<field name="Alarm" units="" type="enum" options="Uninitialised,OK,Warning,Error,Critical" defaultvalue="Uninitialised">
|
<field name="Alarm" units="" type="enum" options="Uninitialised,OK,Warning,Error,Critical" defaultvalue="Uninitialised">
|
||||||
<elementnames>
|
<elementnames>
|
||||||
|
<elementname>SystemConfiguration</elementname>
|
||||||
|
<elementname>BootFault</elementname>
|
||||||
<elementname>OutOfMemory</elementname>
|
<elementname>OutOfMemory</elementname>
|
||||||
<elementname>StackOverflow</elementname>
|
<elementname>StackOverflow</elementname>
|
||||||
<elementname>CPUOverload</elementname>
|
<elementname>CPUOverload</elementname>
|
||||||
<elementname>SystemConfiguration</elementname>
|
|
||||||
<elementname>EventSystem</elementname>
|
<elementname>EventSystem</elementname>
|
||||||
<elementname>Telemetry</elementname>
|
<elementname>Telemetry</elementname>
|
||||||
<elementname>ManualControl</elementname>
|
<elementname>ManualControl</elementname>
|
||||||
@ -19,10 +20,26 @@
|
|||||||
<elementname>FlightTime</elementname>
|
<elementname>FlightTime</elementname>
|
||||||
<elementname>I2C</elementname>
|
<elementname>I2C</elementname>
|
||||||
<elementname>GPS</elementname>
|
<elementname>GPS</elementname>
|
||||||
<elementname>BootFault</elementname>
|
|
||||||
<elementname>Power</elementname>
|
<elementname>Power</elementname>
|
||||||
</elementnames>
|
</elementnames>
|
||||||
</field>
|
</field>
|
||||||
|
<field name="ExtendedAlarmStatus" units="" type="enum" defaultvalue="None">
|
||||||
|
<elementnames>
|
||||||
|
<elementname>SystemConfiguration</elementname>
|
||||||
|
<elementname>BootFault</elementname>
|
||||||
|
</elementnames>
|
||||||
|
<options>
|
||||||
|
<option>None</option>
|
||||||
|
<option>RebootRequired</option>
|
||||||
|
<option>FlightMode</option>
|
||||||
|
</options>
|
||||||
|
</field>
|
||||||
|
<field name="ExtendedAlarmSubStatus" units="" type="uint8" defaultvalue="0">
|
||||||
|
<elementnames>
|
||||||
|
<elementname>SystemConfiguration</elementname>
|
||||||
|
<elementname>BootFault</elementname>
|
||||||
|
</elementnames>
|
||||||
|
</field>
|
||||||
<access gcs="readwrite" flight="readwrite"/>
|
<access gcs="readwrite" flight="readwrite"/>
|
||||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||||
|
Loading…
x
Reference in New Issue
Block a user