1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-03-21 13:28:58 +01:00

Merge remote-tracking branch 'origin/next' into thread/OP-1668_Mixer_Curve_2_Source

This commit is contained in:
m_thread 2015-01-27 13:31:09 +01:00
commit 4f7344121e
126 changed files with 2370 additions and 1841 deletions

View File

@ -81,7 +81,7 @@ $(foreach var, $(SANITIZE_DEPRECATED_VARS), $(eval $(call SANITIZE_VAR,$(var),de
# Make sure this isn't being run as root unless installing (no whoami on Windows, but that is ok here)
ifeq ($(shell whoami 2>/dev/null),root)
ifeq ($(filter install install_qt,$(MAKECMDGOALS)),)
ifeq ($(filter install all_clean,$(MAKECMDGOALS)),)
$(error You should not be running this as root)
endif
endif
@ -783,9 +783,6 @@ ifneq ($(strip $(filter package clean_package,$(MAKECMDGOALS))),)
export PACKAGE_NAME := OpenPilot
export PACKAGE_SEP := -
# Copy the Qt libraries regardless whether the building machine needs them to run GCS
export FORCE_COPY_QT := true
# We can only package release builds
ifneq ($(GCS_BUILD_CONF),release)
$(error Packaging is currently supported for release builds only)
@ -808,24 +805,11 @@ ifneq ($(strip $(filter package clean_package,$(MAKECMDGOALS))),)
endif
endif
# Copy file template. Empty line before the endef is required, do not remove
# $(1) = copy file name without extension
# $(2) = source file extension
# $(3) = destination file extension
define COPY_FW_FILES
$(V1) $(CP) "$(BUILD_DIR)/$(1)/$(1)$(2)" "$(PACKAGE_DIR)/firmware/$(1)$(PACKAGE_SEP)$(PACKAGE_LBL)$(3)"
endef
# Build and copy package files into the package directory
# and call platform-specific packaging script
.PHONY: package
package: all_fw all_ground uavobjects_matlab
@$(ECHO) "Packaging for $(UNAME) $(ARCH) into $(call toprel, $(PACKAGE_DIR)) directory"
$(V1) [ ! -d "$(PACKAGE_DIR)" ] || $(RM) -rf "$(PACKAGE_DIR)"
$(V1) $(MKDIR) -p "$(PACKAGE_DIR)/firmware"
$(foreach fw_targ, $(PACKAGE_FW_TARGETS), $(call COPY_FW_FILES,$(fw_targ),.opfw,.opfw))
$(foreach fw_targ, $(PACKAGE_ELF_TARGETS), $(call COPY_FW_FILES,$(fw_targ),.elf,.elf))
$(V1) $(MKDIR) -p "$(PACKAGE_DIR)"
$(MAKE) --no-print-directory -C $(ROOT_DIR)/package --file=$(UNAME).mk $@
##############################
@ -963,13 +947,6 @@ install:
$(V1) rm $(DESTDIR)/$(datadir)/openpilotgcs/translations/Makefile
.PHONY: install_qt
install_qt:
@$(ECHO) " INSTALLING QT TO $(DESTDIR)/)"
$(V1) $(MKDIR) -p $(DESTDIR)$(libdir)
$(V1) $(INSTALL) $(BUILD_DIR)/openpilotgcs_$(GCS_BUILD_CONF)/lib/qt5 $(DESTDIR)$(libdir)
##############################
#
# Help message, the default Makefile goal
@ -1107,7 +1084,6 @@ help:
@$(ECHO) " opfw_resource - Generate resources to embed firmware binaries into the GCS"
@$(ECHO) " dist - Generate source archive for distribution"
@$(ECHO) " install - Install GCS to \"DESTDIR\" with prefix \"prefix\" (Linux only)"
@$(ECHO) " install_qt - Install QT to \"DESTDIR\" with prefix \"prefix\" (Linux only)"
@$(ECHO)
@$(ECHO) " [Code Formatting]"
@$(ECHO) " uncrustify_<source> - Reformat <source> code according to the project's standards"

View File

@ -30,6 +30,7 @@
#ifndef PLANS_H_
#define PLANS_H_
#include <stdint.h>
#include <pios_math.h>
/** \page standard Plans
@ -67,6 +68,16 @@ void plan_setup_land();
*/
void plan_run_land();
/**
* @brief setup pathplanner/pathfollower for braking
*/
void plan_setup_assistedcontrol(uint8_t timeout_occurred);
#define PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_NORTH 0
#define PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_EAST 1
#define PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_DOWN 2
#define PATHDESIRED_MODEPARAMETER_BRAKE_TIMEOUT 3
/**
* @brief setup pathfollower for positionvario
*/

View File

@ -53,6 +53,6 @@ typedef enum {
extern int32_t configuration_check();
FrameType_t GetCurrentFrameType();
extern FrameType_t GetCurrentFrameType();
#endif /* SANITYCHECK_H */

View File

@ -47,6 +47,7 @@ static void path_circle(PathDesiredData *path, float *cur_point, struct path_sta
void path_progress(PathDesiredData *path, float *cur_point, struct path_status *status)
{
switch (path->Mode) {
case PATHDESIRED_MODE_BRAKE: // should never get here...
case PATHDESIRED_MODE_FLYVECTOR:
return path_vector(path, cur_point, status, true);

View File

@ -35,8 +35,11 @@
#include <pathdesired.h>
#include <positionstate.h>
#include <flightmodesettings.h>
#include <flightstatus.h>
#include <velocitystate.h>
#include <manualcontrolcommand.h>
#include <attitudestate.h>
#include <vtolpathfollowersettings.h>
#include <sin_lookup.h>
#define UPDATE_EXPECTED 0.02f
@ -53,8 +56,11 @@ void plan_initialize()
PositionStateInitialize();
PathDesiredInitialize();
FlightModeSettingsInitialize();
FlightStatusInitialize();
AttitudeStateInitialize();
ManualControlCommandInitialize();
VelocityStateInitialize();
VtolPathFollowerSettingsInitialize();
}
/**
@ -84,6 +90,7 @@ void plan_setup_positionHold()
PathDesiredSet(&pathDesired);
}
/**
* @brief setup pathplanner/pathfollower for return to base
*/
@ -504,3 +511,89 @@ void plan_run_AutoCruise()
pathDesired.Start.Down = pathDesired.End.Down;
PathDesiredSet(&pathDesired);
}
/**
* @brief setup pathplanner/pathfollower for braking in positionroam
* timeout_occurred = false: Attempt to enter flyvector for braking
* timeout_occurred = true: Revert to position hold
*/
#define ASSISTEDCONTROL_BRAKERATE_MINIMUM 0.2f // m/s2
#define ASSISTEDCONTROL_TIMETOSTOP_MINIMUM 0.2f // seconds
#define ASSISTEDCONTROL_TIMETOSTOP_MAXIMUM 9.0f // seconds
#define ASSISTEDCONTROL_DELAY_TO_BRAKE 1.0f // seconds
#define ASSISTEDCONTROL_TIMEOUT_MULTIPLIER 2.0f // actual deceleration rate can be 50% of desired...timeouts need to cater for this
void plan_setup_assistedcontrol(uint8_t timeout_occurred)
{
PositionStateData positionState;
PositionStateGet(&positionState);
PathDesiredData pathDesired;
PathDesiredGet(&pathDesired);
FlightStatusAssistedControlStateOptions assistedControlFlightMode;
FlightStatusAssistedControlStateGet(&assistedControlFlightMode);
if (timeout_occurred) {
pathDesired.End.North = positionState.North;
pathDesired.End.East = positionState.East;
pathDesired.End.Down = positionState.Down;
pathDesired.Start.North = positionState.North;
pathDesired.Start.East = positionState.East;
pathDesired.Start.Down = positionState.Down;
pathDesired.StartingVelocity = 0.0f;
pathDesired.EndingVelocity = 0.0f;
pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT;
assistedControlFlightMode = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_HOLD;
} else {
VelocityStateData velocityState;
VelocityStateGet(&velocityState);
float brakeRate;
VtolPathFollowerSettingsBrakeRateGet(&brakeRate);
if (brakeRate < ASSISTEDCONTROL_BRAKERATE_MINIMUM) {
brakeRate = ASSISTEDCONTROL_BRAKERATE_MINIMUM; // set a minimum to avoid a divide by zero potential below
}
// Calculate the velocity
float velocity = velocityState.North * velocityState.North + velocityState.East * velocityState.East + velocityState.Down * velocityState.Down;
velocity = sqrtf(velocity);
// Calculate the desired time to zero velocity.
float time_to_stopped = ASSISTEDCONTROL_DELAY_TO_BRAKE; // we allow at least 0.5 seconds to rotate to a brake angle.
time_to_stopped += velocity / brakeRate;
// Sanity check the brake rate by ensuring that the time to stop is within a range.
if (time_to_stopped < ASSISTEDCONTROL_TIMETOSTOP_MINIMUM) {
time_to_stopped = ASSISTEDCONTROL_TIMETOSTOP_MINIMUM;
} else if (time_to_stopped > ASSISTEDCONTROL_TIMETOSTOP_MAXIMUM) {
time_to_stopped = ASSISTEDCONTROL_TIMETOSTOP_MAXIMUM;
}
// calculate the distance we will travel
float north_delta = velocityState.North * ASSISTEDCONTROL_DELAY_TO_BRAKE; // we allow at least 0.5s to rotate to brake angle
north_delta += (time_to_stopped - ASSISTEDCONTROL_DELAY_TO_BRAKE) * 0.5f * velocityState.North; // area under the linear deceleration plot
float east_delta = velocityState.East * ASSISTEDCONTROL_DELAY_TO_BRAKE; // we allow at least 0.5s to rotate to brake angle
east_delta += (time_to_stopped - ASSISTEDCONTROL_DELAY_TO_BRAKE) * 0.5f * velocityState.East; // area under the linear deceleration plot
float down_delta = velocityState.Down * ASSISTEDCONTROL_DELAY_TO_BRAKE;
down_delta += (time_to_stopped - ASSISTEDCONTROL_DELAY_TO_BRAKE) * 0.5f * velocityState.Down; // area under the linear deceleration plot
float net_delta = east_delta * east_delta + north_delta * north_delta + down_delta * down_delta;
net_delta = sqrtf(net_delta);
pathDesired.Start.North = positionState.North;
pathDesired.Start.East = positionState.East;
pathDesired.Start.Down = positionState.Down;
pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_NORTH] = velocityState.North;
pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_EAST] = velocityState.East;
pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_DOWN] = velocityState.Down;
pathDesired.End.North = positionState.North + north_delta;
pathDesired.End.East = positionState.East + east_delta;
pathDesired.End.Down = positionState.Down + down_delta;
pathDesired.StartingVelocity = velocity;
pathDesired.EndingVelocity = 0.0f;
pathDesired.Mode = PATHDESIRED_MODE_BRAKE;
pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_TIMEOUT] = time_to_stopped * ASSISTEDCONTROL_TIMEOUT_MULTIPLIER;
assistedControlFlightMode = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE;
}
FlightStatusAssistedControlStateSet(&assistedControlFlightMode);
PathDesiredSet(&pathDesired);
}

View File

@ -36,6 +36,7 @@
#include <manualcontrolsettings.h>
#include <flightmodesettings.h>
#include <systemsettings.h>
#include <stabilizationsettings.h>
#include <systemalarms.h>
#include <revosettings.h>
#include <positionstate.h>
@ -46,7 +47,7 @@
// ! Check a stabilization mode switch position for safety
static bool check_stabilization_settings(int index, bool multirotor, bool coptercontrol);
static bool check_stabilization_settings(int index, bool multirotor, bool coptercontrol, bool gpsassisted);
/**
* Run a preflight check over the hardware configuration
@ -95,31 +96,41 @@ int32_t configuration_check()
// modes
uint8_t num_modes;
uint8_t modes[FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM];
uint8_t FlightModeAssistMap[STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NUMELEM];
ManualControlSettingsFlightModeNumberGet(&num_modes);
StabilizationSettingsFlightModeAssistMapGet(FlightModeAssistMap);
FlightModeSettingsFlightModePositionGet(modes);
for (uint32_t i = 0; i < num_modes; i++) {
uint8_t gps_assisted = FlightModeAssistMap[i];
if (gps_assisted) {
ADDSEVERITY(!coptercontrol);
ADDSEVERITY(multirotor);
ADDSEVERITY(navCapableFusion);
}
switch (modes[i]) {
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_MANUAL:
ADDSEVERITY(!gps_assisted);
ADDSEVERITY(!multirotor);
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED1:
ADDSEVERITY(check_stabilization_settings(1, multirotor, coptercontrol));
ADDSEVERITY(check_stabilization_settings(1, multirotor, coptercontrol, gps_assisted));
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED2:
ADDSEVERITY(check_stabilization_settings(2, multirotor, coptercontrol));
ADDSEVERITY(check_stabilization_settings(2, multirotor, coptercontrol, gps_assisted));
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED3:
ADDSEVERITY(check_stabilization_settings(3, multirotor, coptercontrol));
ADDSEVERITY(check_stabilization_settings(3, multirotor, coptercontrol, gps_assisted));
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED4:
ADDSEVERITY(check_stabilization_settings(4, multirotor, coptercontrol));
ADDSEVERITY(check_stabilization_settings(4, multirotor, coptercontrol, gps_assisted));
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED5:
ADDSEVERITY(check_stabilization_settings(5, multirotor, coptercontrol));
ADDSEVERITY(check_stabilization_settings(5, multirotor, coptercontrol, gps_assisted));
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_STABILIZED6:
ADDSEVERITY(check_stabilization_settings(6, multirotor, coptercontrol));
ADDSEVERITY(check_stabilization_settings(6, multirotor, coptercontrol, gps_assisted));
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_PATHPLANNER:
{
@ -129,9 +140,13 @@ int32_t configuration_check()
SystemAlarmsAlarmData alarms;
SystemAlarmsAlarmGet(&alarms);
ADDSEVERITY(alarms.PathPlan == SYSTEMALARMS_ALARM_OK);
ADDSEVERITY(!gps_assisted);
}
// intentionally no break as this also needs pathfollower
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD:
ADDSEVERITY(!coptercontrol);
ADDSEVERITY(navCapableFusion);
break;
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_COURSELOCK:
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONROAM:
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_HOMELEASH:
@ -140,6 +155,7 @@ int32_t configuration_check()
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POI:
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_RETURNTOBASE:
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_AUTOCRUISE:
ADDSEVERITY(!gps_assisted);
ADDSEVERITY(!coptercontrol);
ADDSEVERITY(navCapableFusion);
break;
@ -175,7 +191,7 @@ int32_t configuration_check()
* @param[in] index Which stabilization mode to check
* @returns true or false
*/
static bool check_stabilization_settings(int index, bool multirotor, bool coptercontrol)
static bool check_stabilization_settings(int index, bool multirotor, bool coptercontrol, bool gpsassisted)
{
uint8_t modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_NUMELEM];
@ -213,6 +229,17 @@ static bool check_stabilization_settings(int index, bool multirotor, bool copter
}
}
if (gpsassisted) {
// For multirotors verify that roll/pitch are either attitude or rattitude
for (uint32_t i = 0; i < FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_YAW; i++) {
if (!(modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ATTITUDE ||
modes[i] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_RATTITUDE)) {
return false;
}
}
}
// coptercontrol cannot do altitude holding
if (coptercontrol) {
if (modes[FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_THRUST] == FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEHOLD

View File

@ -278,9 +278,9 @@ static bool okToArm(void)
StabilizationDesiredStabilizationModeData stabDesired;
uint8_t flightMode;
FlightStatusFlightModeGet(&flightMode);
switch (flightMode) {
FlightStatusData flightStatus;
FlightStatusGet(&flightStatus);
switch (flightStatus.FlightMode) {
case FLIGHTSTATUS_FLIGHTMODE_MANUAL:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2:
@ -293,9 +293,16 @@ static bool okToArm(void)
if (stabDesired.Thrust == STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD ||
stabDesired.Thrust == STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEVARIO) {
return false;
} else {
return true;
}
// avoid assisted control with auto throttle. As it sits waiting to launch,
// it will move to hold, and auto thrust will auto launch otherwise!
if (flightStatus.FlightModeAssist == FLIGHTSTATUS_FLIGHTMODEASSIST_GPSASSIST) {
return false;
}
return true;
break;
default:

View File

@ -37,22 +37,30 @@
#include <sanitycheck.h>
#include <manualcontrolsettings.h>
#include <manualcontrolcommand.h>
#include <vtolselftuningstats.h>
#include <flightmodesettings.h>
#include <flightstatus.h>
#include <systemsettings.h>
#include <stabilizationdesired.h>
#include <callbackinfo.h>
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
#include <stabilizationsettings.h>
#include <vtolpathfollowersettings.h>
#endif
// Private constants
#if defined(PIOS_MANUAL_STACK_SIZE)
#define STACK_SIZE_BYTES PIOS_MANUAL_STACK_SIZE
#define STACK_SIZE_BYTES PIOS_MANUAL_STACK_SIZE
#else
#define STACK_SIZE_BYTES 1152
#define STACK_SIZE_BYTES 1152
#endif
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_REGULAR
#define CBTASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_REGULAR
#define CBTASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL
#define ASSISTEDCONTROL_NEUTRALTHROTTLERANGE_FACTOR 0.2f
#define ASSISTEDCONTROL_BRAKETHRUST_DEADBAND_FACTOR_LO 0.92f
#define ASSISTEDCONTROL_BRAKETHRUST_DEADBAND_FACTOR_HI 1.08f
// defined handlers
@ -93,6 +101,9 @@ static const controlHandler handler_PATHPLANNER = {
},
.handler = &pathPlannerHandler,
};
static float thrustAtBrakeStart = 0.0f;
static float thrustLo = 0.0f;
static float thrustHi = 0.0f;
#endif /* ifndef PIOS_EXCLUDE_ADVANCED_FEATURES */
// Private variables
@ -101,8 +112,10 @@ static DelayedCallbackInfo *callbackHandle;
// Private functions
static void configurationUpdatedCb(UAVObjEvent *ev);
static void commandUpdatedCb(UAVObjEvent *ev);
static void manualControlTask(void);
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
static uint8_t isAssistedFlightMode(uint8_t position, uint8_t flightMode, FlightModeSettingsData *modeSettings);
#endif
#define assumptions (assumptions1 && assumptions2 && assumptions3 && assumptions4 && assumptions5 && assumptions6 && assumptions7 && assumptions_flightmode)
@ -147,7 +160,11 @@ int32_t ManualControlInitialize()
ManualControlSettingsInitialize();
FlightModeSettingsInitialize();
SystemSettingsInitialize();
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
VtolSelfTuningStatsInitialize();
StabilizationSettingsInitialize();
VtolPathFollowerSettingsInitialize();
#endif
callbackHandle = PIOS_CALLBACKSCHEDULER_Create(&manualControlTask, CALLBACK_PRIORITY, CBTASK_PRIORITY, CALLBACKINFO_RUNNING_MANUALCONTROL, STACK_SIZE_BYTES);
return 0;
@ -170,16 +187,36 @@ static void manualControlTask(void)
FlightStatusGet(&flightStatus);
ManualControlCommandData cmd;
ManualControlCommandGet(&cmd);
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
VtolPathFollowerSettingsThrustLimitsData thrustLimits;
VtolPathFollowerSettingsThrustLimitsGet(&thrustLimits);
#endif
FlightModeSettingsData modeSettings;
FlightModeSettingsGet(&modeSettings);
uint8_t position = cmd.FlightModeSwitchPosition;
uint8_t newMode = flightStatus.FlightMode;
uint8_t newFlightModeAssist = flightStatus.FlightModeAssist;
uint8_t newAssistedControlState = flightStatus.AssistedControlState;
uint8_t newAssistedThrottleState = flightStatus.AssistedThrottleState;
if (position < FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM) {
newMode = modeSettings.FlightModePosition[position];
}
// if a mode change occurs we default the assist mode and states here
// to avoid having to add it to all of the below modes that are
// otherwise unrelated
if (newMode != flightStatus.FlightMode) {
// set assist mode to none to avoid an assisted flight mode position
// carrying over and impacting a newly selected non-assisted flight mode pos
newFlightModeAssist = FLIGHTSTATUS_FLIGHTMODEASSIST_NONE;
// The following are eqivalent to none effectively. Code should always
// check the flightmodeassist state.
newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_PRIMARY;
newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL;
}
// Depending on the mode update the Stabilization or Actuator objects
const controlHandler *handler = &handler_MANUAL;
switch (newMode) {
@ -193,9 +230,173 @@ static void manualControlTask(void)
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6:
handler = &handler_STABILIZED;
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
newFlightModeAssist = isAssistedFlightMode(position, newMode, &modeSettings);
if (newFlightModeAssist) {
// assess roll/pitch state
bool flagRollPitchHasInput = (fabsf(cmd.Roll) > 0.0f || fabsf(cmd.Pitch) > 0.0f);
// assess throttle state
bool throttleNeutral = false;
bool throttleNeutralOrLow = false;
float neutralThrustOffset = 0.0f;
VtolSelfTuningStatsNeutralThrustOffsetGet(&neutralThrustOffset);
float throttleRangeDelta = (thrustLimits.Neutral + neutralThrustOffset) * ASSISTEDCONTROL_NEUTRALTHROTTLERANGE_FACTOR;
float throttleNeutralLow = (thrustLimits.Neutral + neutralThrustOffset) - throttleRangeDelta;
float throttleNeutralHi = (thrustLimits.Neutral + neutralThrustOffset) + throttleRangeDelta;
if (cmd.Thrust > throttleNeutralLow && cmd.Thrust < throttleNeutralHi) {
throttleNeutral = true;
}
if (cmd.Thrust < throttleNeutralHi) {
throttleNeutralOrLow = true;
}
// determine default thrust mode for hold/brake states
uint8_t pathfollowerthrustmode = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL;
if (newFlightModeAssist == FLIGHTSTATUS_FLIGHTMODEASSIST_GPSASSIST) {
pathfollowerthrustmode = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_AUTO;
}
switch (newAssistedControlState) {
case FLIGHTSTATUS_ASSISTEDCONTROLSTATE_PRIMARY:
if (!flagRollPitchHasInput) {
// no stick input on roll/pitch so enter brake state
newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE;
newAssistedThrottleState = pathfollowerthrustmode;
handler = &handler_PATHFOLLOWER;
// retain thrust cmd for later comparison with actual in braking
thrustAtBrakeStart = cmd.Thrust;
// calculate hi and low value of +-8% as a mini-deadband
// for use in auto-override in brake sequence
thrustLo = ASSISTEDCONTROL_BRAKETHRUST_DEADBAND_FACTOR_LO * thrustAtBrakeStart;
thrustHi = ASSISTEDCONTROL_BRAKETHRUST_DEADBAND_FACTOR_HI * thrustAtBrakeStart;
// The purpose for auto throttle assist is to go from a mid to high thrust range to a
// neutral vertical-holding/maintaining ~50% thrust range. It is not designed/intended
// to go from near zero to 50%...we don't want an auto-takeoff feature here!
// Also for rapid decents a user might have a bit of forward stick and low throttle
// then stick-off for auto-braking...but if below the vtol min of 20% it will not
// kick in...the flyer needs to manually manage throttle to slow down decent,
// and the next time they put in a bit of stick, revert to primary, and then
// sticks-off it will brake and hold with auto-thrust
if (thrustAtBrakeStart < thrustLimits.Min) {
newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL; // Effectively None
}
} else {
// stick input so stay in primary mode control state
// newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_PRIMARY;
newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL; // Effectively None
}
break;
case FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE:
if (flagRollPitchHasInput) {
// stick input during brake sequence allows immediate resumption of control
newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_PRIMARY;
newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL; // Effectively None
} else {
// no stick input, stay in brake mode
newAssistedThrottleState = pathfollowerthrustmode;
handler = &handler_PATHFOLLOWER;
// if auto thrust and user adjusts thrust outside of a deadband in which case revert to manual
if ((newAssistedThrottleState == FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_AUTO) &&
(cmd.Thrust < thrustLo || cmd.Thrust > thrustHi)) {
newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL;
}
}
break;
case FLIGHTSTATUS_ASSISTEDCONTROLSTATE_HOLD:
if (newFlightModeAssist == FLIGHTSTATUS_FLIGHTMODEASSIST_GPSASSIST_PRIMARYTHRUST ||
(newFlightModeAssist == FLIGHTSTATUS_FLIGHTMODEASSIST_GPSASSIST &&
newAssistedThrottleState == FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL)) {
// for manual or primary throttle states/modes, stick control immediately reverts to primary mode control
if (flagRollPitchHasInput) {
newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_PRIMARY;
newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL; // Effectively None
} else {
// otherwise stay in the hold state
// newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_HOLD;
newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL;
handler = &handler_PATHFOLLOWER;
}
} else if (newFlightModeAssist == FLIGHTSTATUS_FLIGHTMODEASSIST_GPSASSIST &&
newAssistedThrottleState != FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL) {
// ok auto thrust mode applies in hold unless overridden
if (throttleNeutralOrLow && flagRollPitchHasInput) {
// throttle is neutral approximately and stick input present so revert to primary mode control
newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_PRIMARY;
newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL; // Effectively None
} else {
// otherwise hold, autothrust, no stick input...we watch throttle for need to change mode
switch (newAssistedThrottleState) {
case FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_AUTO:
// whilst in auto, watch for neutral range, from which we allow override
if (throttleNeutral) {
pathfollowerthrustmode = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_AUTOOVERRIDE;
} else { pathfollowerthrustmode = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_AUTO; }
break;
case FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_AUTOOVERRIDE:
// previously user has set throttle to neutral range, apply a deadband and revert to manual
// if moving out of deadband. This allows for landing in hold state.
if (!throttleNeutral) {
pathfollowerthrustmode = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL;
} else { pathfollowerthrustmode = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_AUTOOVERRIDE; }
break;
case FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL:
pathfollowerthrustmode = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL;
break;
}
newAssistedThrottleState = pathfollowerthrustmode;
handler = &handler_PATHFOLLOWER;
}
}
break;
}
}
#endif /* ifndef PIOS_EXCLUDE_ADVANCED_FEATURES */
break;
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
newFlightModeAssist = isAssistedFlightMode(position, newMode, &modeSettings);
if (newFlightModeAssist) {
switch (newFlightModeAssist) {
case FLIGHTSTATUS_FLIGHTMODEASSIST_GPSASSIST_PRIMARYTHRUST:
newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL;
break;
case FLIGHTSTATUS_FLIGHTMODEASSIST_GPSASSIST:
newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_AUTO;
break;
case FLIGHTSTATUS_FLIGHTMODEASSIST_NONE:
default:
newAssistedThrottleState = FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL; // Effectively None
break;
}
switch (newAssistedControlState) {
case FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE:
newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE;
break;
case FLIGHTSTATUS_ASSISTEDCONTROLSTATE_PRIMARY:
newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE;
break;
case FLIGHTSTATUS_ASSISTEDCONTROLSTATE_HOLD:
newAssistedControlState = FLIGHTSTATUS_ASSISTEDCONTROLSTATE_HOLD;
break;
}
}
handler = &handler_PATHFOLLOWER;
break;
case FLIGHTSTATUS_FLIGHTMODE_COURSELOCK:
case FLIGHTSTATUS_FLIGHTMODE_POSITIONROAM:
case FLIGHTSTATUS_FLIGHTMODE_HOMELEASH:
@ -209,7 +410,7 @@ static void manualControlTask(void)
case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER:
handler = &handler_PATHPLANNER;
break;
#endif
#endif /* ifndef PIOS_EXCLUDE_ADVANCED_FEATURES */
// There is no default, so if a flightmode is forgotten the compiler can throw a warning!
}
@ -218,10 +419,16 @@ static void manualControlTask(void)
// FlightMode needs to be set correctly on first run (otherwise ControlChain is invalid)
static bool firstRun = true;
if (flightStatus.FlightMode != newMode || firstRun) {
if (flightStatus.FlightMode != newMode || firstRun ||
newFlightModeAssist != flightStatus.FlightModeAssist ||
newAssistedControlState != flightStatus.AssistedControlState ||
flightStatus.AssistedThrottleState != newAssistedThrottleState) {
firstRun = false;
flightStatus.ControlChain = handler->controlChain;
flightStatus.FlightMode = newMode;
flightStatus.ControlChain = handler->controlChain;
flightStatus.FlightMode = newMode;
flightStatus.FlightModeAssist = newFlightModeAssist;
flightStatus.AssistedControlState = newAssistedControlState;
flightStatus.AssistedThrottleState = newAssistedThrottleState;
FlightStatusSet(&flightStatus);
newinit = true;
}
@ -246,6 +453,81 @@ static void commandUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
PIOS_CALLBACKSCHEDULER_Dispatch(callbackHandle);
}
/**
* Check and set modes for gps assisted stablised flight modes
*/
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
static uint8_t isAssistedFlightMode(uint8_t position, uint8_t flightMode, FlightModeSettingsData *modeSettings)
{
uint8_t flightModeAssistOption = STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NONE;
uint8_t isAssistedFlag = FLIGHTSTATUS_FLIGHTMODEASSIST_NONE;
uint8_t FlightModeAssistMap[STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NUMELEM];
StabilizationSettingsFlightModeAssistMapGet(FlightModeAssistMap);
if (position < STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NUMELEM) {
flightModeAssistOption = FlightModeAssistMap[position];
}
switch (flightModeAssistOption) {
case STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NONE:
break;
case STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_GPSASSIST:
{
// default to cruise control.
FlightModeSettingsStabilization1SettingsOptions thrustMode = FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL;
switch (flightMode) {
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1:
thrustMode = modeSettings->Stabilization1Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2:
thrustMode = modeSettings->Stabilization2Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3:
thrustMode = modeSettings->Stabilization3Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED4:
thrustMode = modeSettings->Stabilization4Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5:
thrustMode = modeSettings->Stabilization5Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6:
thrustMode = modeSettings->Stabilization6Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
// we hard code the "GPS Assisted" PostionHold to use alt-vario which
// is a more appropriate throttle mode. "GPSAssist" adds braking
// and a better throttle management to the standard Position Hold.
thrustMode = FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEVARIO;
break;
// other modes will use cruisecontrol as default
}
switch (thrustMode) {
case FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEHOLD:
case FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEVARIO:
// this is only for use with stabi mods with althold/vario.
isAssistedFlag = FLIGHTSTATUS_FLIGHTMODEASSIST_GPSASSIST_PRIMARYTHRUST;
break;
case FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_MANUAL:
case FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL:
default:
// this is the default for non stabi modes also
isAssistedFlag = FLIGHTSTATUS_FLIGHTMODEASSIST_GPSASSIST;
break;
}
}
break;
}
return isAssistedFlag;
}
#endif /* ifndef PIOS_EXCLUDE_ADVANCED_FEATURES */
/**
* @}
* @}

View File

@ -56,7 +56,9 @@ void pathFollowerHandler(bool newinit)
}
uint8_t flightMode;
uint8_t assistedControlFlightMode;
FlightStatusFlightModeGet(&flightMode);
FlightStatusAssistedControlStateGet(&assistedControlFlightMode);
if (newinit) {
// After not being in this mode for a while init at current height
@ -64,9 +66,13 @@ void pathFollowerHandler(bool newinit)
case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE:
plan_setup_returnToBase();
break;
case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
plan_setup_positionHold();
if (assistedControlFlightMode == FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE) {
// Just initiated braking after returning from stabi control
plan_setup_assistedcontrol(false);
} else {
plan_setup_positionHold();
}
break;
case FLIGHTSTATUS_FLIGHTMODE_COURSELOCK:
plan_setup_CourseLock();
@ -88,6 +94,18 @@ void pathFollowerHandler(bool newinit)
plan_setup_AutoCruise();
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED4:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5:
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6:
if (assistedControlFlightMode == FLIGHTSTATUS_ASSISTEDCONTROLSTATE_BRAKE) {
// Just initiated braking after returning from stabi control
plan_setup_assistedcontrol(false);
}
break;
default:
plan_setup_positionHold();
break;

View File

@ -93,6 +93,7 @@ void stabilizedHandler(bool newinit)
uint8_t *stab_settings;
FlightStatusData flightStatus;
FlightStatusGet(&flightStatus);
switch (flightStatus.FlightMode) {
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1:
stab_settings = FlightModeSettingsStabilization1SettingsToArray(settings.Stabilization1Settings);
@ -163,8 +164,8 @@ void stabilizedHandler(bool newinit)
0; // this is an invalid mode
}
stabilization.Thrust = cmd.Thrust;
stabilization.StabilizationMode.Thrust = stab_settings[3];
stabilization.Thrust = cmd.Thrust;
StabilizationDesiredSet(&stabilization);
}

View File

@ -54,6 +54,7 @@
#include <sin_lookup.h>
#include <pathdesired.h>
#include <paths.h>
#include "plans.h"
#include <sanitycheck.h>
@ -61,6 +62,7 @@
#include <fixedwingpathfollowerstatus.h>
#include <vtolpathfollowersettings.h>
#include <flightstatus.h>
#include <flightmodesettings.h>
#include <pathstatus.h>
#include <positionstate.h>
#include <velocitystate.h>
@ -73,25 +75,42 @@
#include <manualcontrolcommand.h>
#include <systemsettings.h>
#include <stabilizationbank.h>
#include <vtolselftuningstats.h>
#include <pathsummary.h>
// Private constants
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_LOW
#define CBTASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_LOW
#define CBTASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL
#define PF_IDLE_UPDATE_RATE_MS 100
#define PF_IDLE_UPDATE_RATE_MS 100
#define STACK_SIZE_BYTES 2048
#define STACK_SIZE_BYTES 2048
#define DEADBAND_HIGH 0.10f
#define DEADBAND_LOW -0.10f
#define BRAKE_FRACTIONALPROGRESS_STARTVELOCITYCHECK 0.95f
#define BRAKE_EXIT_VELOCITY_LIMIT 0.2f
#define BRAKE_RATE_MINIMUM 0.2f
#define NEUTRALTHRUST_PH_POSITIONAL_ERROR_LIMIT 0.5f
#define NEUTRALTHRUST_PH_VEL_DESIRED_LIMIT 0.2f
#define NEUTRALTHRUST_PH_VEL_STATE_LIMIT 0.2f
#define NEUTRALTHRUST_PH_VEL_ERROR_LIMIT 0.1f
#define NEUTRALTHRUST_START_DELAY (2 * 20) // 2 seconds at rate of 20Hz (50ms update rate)
#define NEUTRALTHRUST_END_COUNT (NEUTRALTHRUST_START_DELAY + (4 * 20)) // 4 second sample
#define DEADBAND_HIGH 0.10f
#define DEADBAND_LOW -0.10f
// Private types
struct Globals {
struct pid PIDposH[2];
struct pid PIDposV;
struct pid PIDvel[3];
struct pid PIDvel[3]; // North, East, Down
struct pid BrakePIDvel[2]; // North, East
struct pid PIDcourse;
struct pid PIDspeed;
struct pid PIDpower;
@ -100,6 +119,19 @@ struct Globals {
bool vtolEmergencyFallbackSwitch;
};
struct NeutralThrustEstimation {
uint32_t count;
float sum;
float average;
float correction;
float algo_erro_check;
float min;
float max;
bool start_sampling;
bool have_correction;
};
static struct NeutralThrustEstimation neutralThrustEst;
// Private variables
static DelayedCallbackInfo *pathFollowerCBInfo;
@ -109,6 +141,8 @@ static PathStatusData pathStatus;
static PathDesiredData pathDesired;
static FixedWingPathFollowerSettingsData fixedWingPathFollowerSettings;
static VtolPathFollowerSettingsData vtolPathFollowerSettings;
static FlightStatusData flightStatus;
static PathSummaryData pathSummary;
// correct speed by measured airspeed
static float indicatedAirspeedStateBias = 0.0f;
@ -126,6 +160,7 @@ static float updateCourseBearing();
static float updatePathBearing();
static float updatePOIBearing();
static void processPOI();
static void updateBrakeVelocity(float startingVelocity, float dT, float brakeRate, float currentVelocity, float *updatedVelocity);
static void updatePathVelocity(float kFF, bool limited);
static uint8_t updateFixedDesiredAttitude();
static int8_t updateVtolDesiredAttitude(bool yaw_attitude, float yaw_direction);
@ -159,7 +194,9 @@ int32_t PathFollowerInitialize()
FixedWingPathFollowerStatusInitialize();
VtolPathFollowerSettingsInitialize();
FlightStatusInitialize();
FlightModeSettingsInitialize();
PathStatusInitialize();
PathSummaryInitialize();
PathDesiredInitialize();
PositionStateInitialize();
VelocityStateInitialize();
@ -172,6 +209,8 @@ int32_t PathFollowerInitialize()
ManualControlCommandInitialize();
SystemSettingsInitialize();
StabilizationBankInitialize();
VtolSelfTuningStatsInitialize();
// reset integrals
resetGlobals();
@ -193,8 +232,6 @@ MODULE_INITCALL(PathFollowerInitialize, PathFollowerStart);
*/
static void pathFollowerTask(void)
{
FlightStatusData flightStatus;
FlightStatusGet(&flightStatus);
if (flightStatus.ControlChain.PathFollower != FLIGHTSTATUS_CONTROLCHAIN_TRUE) {
@ -208,11 +245,21 @@ static void pathFollowerTask(void)
processPOI();
}
int16_t old_uid = pathStatus.UID;
pathStatus.UID = pathDesired.UID;
pathStatus.Status = PATHSTATUS_STATUS_INPROGRESS;
if (pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_TIMEOUT] > 0.0f) {
if (old_uid != pathStatus.UID) {
pathStatus.path_time = 0.0f;
} else {
pathStatus.path_time += updatePeriod / 1000.0f;
}
}
switch (pathDesired.Mode) {
case PATHDESIRED_MODE_FLYENDPOINT:
case PATHDESIRED_MODE_FLYVECTOR:
case PATHDESIRED_MODE_BRAKE:
case PATHDESIRED_MODE_FLYCIRCLERIGHT:
case PATHDESIRED_MODE_FLYCIRCLELEFT:
{
@ -239,6 +286,7 @@ static void pathFollowerTask(void)
}
PathStatusSet(&pathStatus);
PIOS_CALLBACKSCHEDULER_Schedule(pathFollowerCBInfo, updatePeriod, CALLBACK_UPDATEMODE_SOONER);
}
@ -258,6 +306,9 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
pid_configure(&global.PIDvel[1], vtolPathFollowerSettings.HorizontalVelPID.Kp, vtolPathFollowerSettings.HorizontalVelPID.Ki, vtolPathFollowerSettings.HorizontalVelPID.Kd, vtolPathFollowerSettings.HorizontalVelPID.ILimit);
pid_configure(&global.PIDvel[2], vtolPathFollowerSettings.VerticalVelPID.Kp, vtolPathFollowerSettings.VerticalVelPID.Ki, vtolPathFollowerSettings.VerticalVelPID.Kd, vtolPathFollowerSettings.VerticalVelPID.ILimit);
pid_configure(&global.BrakePIDvel[0], vtolPathFollowerSettings.BrakeHorizontalVelPID.Kp, vtolPathFollowerSettings.BrakeHorizontalVelPID.Ki, vtolPathFollowerSettings.BrakeHorizontalVelPID.Kd, vtolPathFollowerSettings.BrakeHorizontalVelPID.ILimit);
pid_configure(&global.BrakePIDvel[1], vtolPathFollowerSettings.BrakeHorizontalVelPID.Kp, vtolPathFollowerSettings.BrakeHorizontalVelPID.Ki, vtolPathFollowerSettings.BrakeHorizontalVelPID.Kd, vtolPathFollowerSettings.BrakeHorizontalVelPID.ILimit);
PathDesiredGet(&pathDesired);
}
@ -297,12 +348,27 @@ static void resetGlobals()
pid_zero(&global.PIDvel[0]);
pid_zero(&global.PIDvel[1]);
pid_zero(&global.PIDvel[2]);
pid_zero(&global.BrakePIDvel[0]);
pid_zero(&global.BrakePIDvel[1]);
pid_zero(&global.PIDcourse);
pid_zero(&global.PIDspeed);
pid_zero(&global.PIDpower);
global.poiRadius = 0.0f;
global.vtolEmergencyFallback = 0;
global.vtolEmergencyFallbackSwitch = false;
// reset neutral thrust assessment. We restart this process
// and do once for each position hold engagement
neutralThrustEst.start_sampling = false;
neutralThrustEst.count = 0;
neutralThrustEst.sum = 0.0f;
neutralThrustEst.have_correction = false;
neutralThrustEst.average = 0.0f;
neutralThrustEst.correction = 0.0f;
neutralThrustEst.min = 0.0f;
neutralThrustEst.max = 0.0f;
pathStatus.path_time = 0.0f;
}
static uint8_t updateAutoPilotByFrameType()
@ -389,28 +455,37 @@ static uint8_t updateAutoPilotVtol()
// yaw behaviour is configurable in vtolpathfollower, select yaw control algorithm
bool yaw_attitude = true;
float yaw = 0.0f;
switch (vtolPathFollowerSettings.YawControl) {
case VTOLPATHFOLLOWERSETTINGS_YAWCONTROL_MANUAL:
if (pathDesired.Mode == PATHDESIRED_MODE_BRAKE) {
yaw_attitude = false;
break;
case VTOLPATHFOLLOWERSETTINGS_YAWCONTROL_TAILIN:
yaw = updateTailInBearing();
break;
case VTOLPATHFOLLOWERSETTINGS_YAWCONTROL_MOVEMENTDIRECTION:
yaw = updateCourseBearing();
break;
case VTOLPATHFOLLOWERSETTINGS_YAWCONTROL_PATHDIRECTION:
yaw = updatePathBearing();
break;
case VTOLPATHFOLLOWERSETTINGS_YAWCONTROL_POI:
yaw = updatePOIBearing();
break;
} else {
switch (vtolPathFollowerSettings.YawControl) {
case VTOLPATHFOLLOWERSETTINGS_YAWCONTROL_MANUAL:
yaw_attitude = false;
break;
case VTOLPATHFOLLOWERSETTINGS_YAWCONTROL_TAILIN:
yaw = updateTailInBearing();
break;
case VTOLPATHFOLLOWERSETTINGS_YAWCONTROL_MOVEMENTDIRECTION:
yaw = updateCourseBearing();
break;
case VTOLPATHFOLLOWERSETTINGS_YAWCONTROL_PATHDIRECTION:
yaw = updatePathBearing();
break;
case VTOLPATHFOLLOWERSETTINGS_YAWCONTROL_POI:
yaw = updatePOIBearing();
break;
}
}
result = updateVtolDesiredAttitude(yaw_attitude, yaw);
// switch to emergency follower if follower indicates problems
if (!result && (vtolPathFollowerSettings.FlyawayEmergencyFallback != VTOLPATHFOLLOWERSETTINGS_FLYAWAYEMERGENCYFALLBACK_DISABLED)) {
global.vtolEmergencyFallbackSwitch = true;
if (!result) {
if (pathDesired.Mode == PATHDESIRED_MODE_BRAKE) {
plan_setup_assistedcontrol(true); // revert braking to position hold, user can always stick override
} else if (vtolPathFollowerSettings.FlyawayEmergencyFallback != VTOLPATHFOLLOWERSETTINGS_FLYAWAYEMERGENCYFALLBACK_DISABLED) {
// switch to emergency follower if follower indicates problems
global.vtolEmergencyFallbackSwitch = true;
}
}
}
break;
@ -427,6 +502,48 @@ static uint8_t updateAutoPilotVtol()
break;
}
// Brake mode end condition checks
if (pathDesired.Mode == PATHDESIRED_MODE_BRAKE) {
bool exit_brake = false;
VelocityStateData velocityState;
if (pathStatus.path_time > pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_TIMEOUT]) { // enter hold on timeout
pathSummary.brake_exit_reason = PATHSUMMARY_BRAKE_EXIT_REASON_TIMEOUT;
exit_brake = true;
} else if (pathStatus.fractional_progress > BRAKE_FRACTIONALPROGRESS_STARTVELOCITYCHECK) {
VelocityStateGet(&velocityState);
if (fabsf(velocityState.East) < BRAKE_EXIT_VELOCITY_LIMIT && fabsf(velocityState.North) < BRAKE_EXIT_VELOCITY_LIMIT) {
pathSummary.brake_exit_reason = PATHSUMMARY_BRAKE_EXIT_REASON_PATHCOMPLETED;
exit_brake = true;
}
}
if (exit_brake) {
// Calculate the distance error between the originally desired
// stopping point and the actual brake-exit point.
PositionStateData p;
PositionStateGet(&p);
float north_offset = pathDesired.End.North - p.North;
float east_offset = pathDesired.End.East - p.East;
float down_offset = pathDesired.End.Down - p.Down;
pathSummary.brake_distance_offset = sqrtf(north_offset * north_offset + east_offset * east_offset + down_offset * down_offset);
pathSummary.time_remaining = pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_TIMEOUT] - pathStatus.path_time;
pathSummary.fractional_progress = pathStatus.fractional_progress;
float cur_velocity = velocityState.North * velocityState.North + velocityState.East * velocityState.East + velocityState.Down * velocityState.Down;
cur_velocity = sqrtf(cur_velocity);
pathSummary.decelrate = (pathDesired.StartingVelocity - cur_velocity) / pathStatus.path_time;
pathSummary.brakeRateActualDesiredRatio = pathSummary.decelrate / vtolPathFollowerSettings.BrakeRate;
pathSummary.velocityIntoHold = cur_velocity;
pathSummary.UID = pathStatus.UID;
PathSummarySet(&pathSummary);
plan_setup_assistedcontrol(true); // braking timeout true
// having re-entered hold allow reassessment of neutral thrust
neutralThrustEst.have_correction = false;
}
}
switch (returnmode) {
case RETURN_RESULT:
return result;
@ -607,6 +724,28 @@ static void processPOI()
}
}
static void updateBrakeVelocity(float startingVelocity, float dT, float brakeRate, float currentVelocity, float *updatedVelocity)
{
if (startingVelocity >= 0.0f) {
*updatedVelocity = startingVelocity - dT * brakeRate;
if (*updatedVelocity > currentVelocity) {
*updatedVelocity = currentVelocity;
}
if (*updatedVelocity < 0.0f) {
*updatedVelocity = 0.0f;
}
} else {
*updatedVelocity = startingVelocity + dT * brakeRate;
if (*updatedVelocity < currentVelocity) {
*updatedVelocity = currentVelocity;
}
if (*updatedVelocity > 0.0f) {
*updatedVelocity = 0.0f;
}
}
}
/**
* Compute desired velocity from the current position and path
*/
@ -617,57 +756,91 @@ static void updatePathVelocity(float kFF, bool limited)
PositionStateGet(&positionState);
VelocityStateData velocityState;
VelocityStateGet(&velocityState);
VelocityDesiredData velocityDesired;
const float dT = updatePeriod / 1000.0f;
// look ahead kFF seconds
float cur[3] = { positionState.North + (velocityState.North * kFF),
positionState.East + (velocityState.East * kFF),
positionState.Down + (velocityState.Down * kFF) };
struct path_status progress;
if (pathDesired.Mode == PATHDESIRED_MODE_BRAKE) {
float brakeRate = vtolPathFollowerSettings.BrakeRate;
if (brakeRate < BRAKE_RATE_MINIMUM) {
brakeRate = BRAKE_RATE_MINIMUM; // set a minimum to avoid a divide by zero potential below
}
updateBrakeVelocity(pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_NORTH], pathStatus.path_time, brakeRate, velocityState.North, &velocityDesired.North);
updateBrakeVelocity(pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_EAST], pathStatus.path_time, brakeRate, velocityState.East, &velocityDesired.East);
updateBrakeVelocity(pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_BRAKE_STARTVELOCITYVECTOR_DOWN], pathStatus.path_time, brakeRate, velocityState.Down, &velocityDesired.Down);
path_progress(&pathDesired, cur, &progress);
float cur_velocity = velocityState.North * velocityState.North + velocityState.East * velocityState.East + velocityState.Down * velocityState.Down;
cur_velocity = sqrtf(cur_velocity);
float desired_velocity = velocityDesired.North * velocityDesired.North + velocityDesired.East * velocityDesired.East + velocityDesired.Down * velocityDesired.Down;
desired_velocity = sqrtf(desired_velocity);
// calculate velocity - can be zero if waypoints are too close
VelocityDesiredData velocityDesired;
velocityDesired.North = progress.path_vector[0];
velocityDesired.East = progress.path_vector[1];
velocityDesired.Down = progress.path_vector[2];
// update pathstatus
pathStatus.error = cur_velocity - desired_velocity;
pathStatus.fractional_progress = 1.0f;
if (pathDesired.StartingVelocity > 0.0f) {
pathStatus.fractional_progress = (pathDesired.StartingVelocity - cur_velocity) / pathDesired.StartingVelocity;
if (limited &&
// if a plane is crossing its desired flightpath facing the wrong way (away from flight direction)
// it would turn towards the flightpath to get on its desired course. This however would reverse the correction vector
// once it crosses the flightpath again, which would make it again turn towards the flightpath (but away from its desired heading)
// leading to an S-shape snake course the wrong way
// this only happens especially if HorizontalPosP is too high, as otherwise the angle between velocity desired and path_direction won't
// turn steep unless there is enough space complete the turn before crossing the flightpath
// in this case the plane effectively needs to be turned around
// indicators:
// difference between correction_direction and velocitystate >90 degrees and
// difference between path_direction and velocitystate >90 degrees ( 4th sector, facing away from everything )
// fix: ignore correction, steer in path direction until the situation has become better (condition doesn't apply anymore)
// calculating angles < 90 degrees through dot products
(vector_lengthf(progress.path_vector, 2) > 1e-6f) &&
((progress.path_vector[0] * velocityState.North + progress.path_vector[1] * velocityState.East) < 0.0f) &&
((progress.correction_vector[0] * velocityState.North + progress.correction_vector[1] * velocityState.East) < 0.0f)) {
;
// sometimes current velocity can exceed starting velocity due to initial acceleration
if (pathStatus.fractional_progress < 0.0f) {
pathStatus.fractional_progress = 0.0f;
}
}
pathStatus.path_direction_north = velocityDesired.North;
pathStatus.path_direction_east = velocityDesired.East;
pathStatus.path_direction_down = velocityDesired.Down;
pathStatus.correction_direction_north = velocityDesired.North - velocityState.North;
pathStatus.correction_direction_east = velocityDesired.East - velocityState.East;
pathStatus.correction_direction_down = velocityDesired.Down - velocityState.Down;
} else {
// calculate correction
velocityDesired.North += pid_apply(&global.PIDposH[0], progress.correction_vector[0], dT);
velocityDesired.East += pid_apply(&global.PIDposH[1], progress.correction_vector[1], dT);
// look ahead kFF seconds
float cur[3] = { positionState.North + (velocityState.North * kFF),
positionState.East + (velocityState.East * kFF),
positionState.Down + (velocityState.Down * kFF) };
struct path_status progress;
path_progress(&pathDesired, cur, &progress);
// calculate velocity - can be zero if waypoints are too close
velocityDesired.North = progress.path_vector[0];
velocityDesired.East = progress.path_vector[1];
velocityDesired.Down = progress.path_vector[2];
if (limited &&
// if a plane is crossing its desired flightpath facing the wrong way (away from flight direction)
// it would turn towards the flightpath to get on its desired course. This however would reverse the correction vector
// once it crosses the flightpath again, which would make it again turn towards the flightpath (but away from its desired heading)
// leading to an S-shape snake course the wrong way
// this only happens especially if HorizontalPosP is too high, as otherwise the angle between velocity desired and path_direction won't
// turn steep unless there is enough space complete the turn before crossing the flightpath
// in this case the plane effectively needs to be turned around
// indicators:
// difference between correction_direction and velocitystate >90 degrees and
// difference between path_direction and velocitystate >90 degrees ( 4th sector, facing away from everything )
// fix: ignore correction, steer in path direction until the situation has become better (condition doesn't apply anymore)
// calculating angles < 90 degrees through dot products
(vector_lengthf(progress.path_vector, 2) > 1e-6f) &&
((progress.path_vector[0] * velocityState.North + progress.path_vector[1] * velocityState.East) < 0.0f) &&
((progress.correction_vector[0] * velocityState.North + progress.correction_vector[1] * velocityState.East) < 0.0f)) {
;
} else {
// calculate correction
velocityDesired.North += pid_apply(&global.PIDposH[0], progress.correction_vector[0], dT);
velocityDesired.East += pid_apply(&global.PIDposH[1], progress.correction_vector[1], dT);
}
velocityDesired.Down += pid_apply(&global.PIDposV, progress.correction_vector[2], dT);
// update pathstatus
pathStatus.error = progress.error;
pathStatus.fractional_progress = progress.fractional_progress;
pathStatus.path_direction_north = progress.path_vector[0];
pathStatus.path_direction_east = progress.path_vector[1];
pathStatus.path_direction_down = progress.path_vector[2];
pathStatus.correction_direction_north = progress.correction_vector[0];
pathStatus.correction_direction_east = progress.correction_vector[1];
pathStatus.correction_direction_down = progress.correction_vector[2];
}
velocityDesired.Down += pid_apply(&global.PIDposV, progress.correction_vector[2], dT);
// update pathstatus
pathStatus.error = progress.error;
pathStatus.fractional_progress = progress.fractional_progress;
pathStatus.path_direction_north = progress.path_vector[0];
pathStatus.path_direction_east = progress.path_vector[1];
pathStatus.path_direction_down = progress.path_vector[2];
pathStatus.correction_direction_north = progress.correction_vector[0];
pathStatus.correction_direction_east = progress.correction_vector[1];
pathStatus.correction_direction_down = progress.correction_vector[2];
VelocityDesiredSet(&velocityDesired);
}
@ -1036,8 +1209,9 @@ static bool correctCourse(float *C, float *V, float *F, float s)
*/
static int8_t updateVtolDesiredAttitude(bool yaw_attitude, float yaw_direction)
{
const float dT = updatePeriod / 1000.0f;
uint8_t result = 1;
const float dT = updatePeriod / 1000.0f;
uint8_t result = 1;
bool manual_thrust = false;
VelocityDesiredData velocityDesired;
VelocityStateData velocityState;
@ -1045,6 +1219,7 @@ static int8_t updateVtolDesiredAttitude(bool yaw_attitude, float yaw_direction)
AttitudeStateData attitudeState;
StabilizationBankData stabSettings;
SystemSettingsData systemSettings;
VtolSelfTuningStatsData vtolSelfTuningStats;
float northError;
float northCommand;
@ -1062,36 +1237,121 @@ static int8_t updateVtolDesiredAttitude(bool yaw_attitude, float yaw_direction)
VelocityDesiredGet(&velocityDesired);
AttitudeStateGet(&attitudeState);
StabilizationBankGet(&stabSettings);
VtolSelfTuningStatsGet(&vtolSelfTuningStats);
// Testing code - refactor into manual control command
ManualControlCommandData manualControlData;
ManualControlCommandGet(&manualControlData);
// scale velocity if it is above configured maximum
float velH = sqrtf(velocityDesired.North * velocityDesired.North + velocityDesired.East * velocityDesired.East);
if (velH > vtolPathFollowerSettings.HorizontalVelMax) {
velocityDesired.North *= vtolPathFollowerSettings.HorizontalVelMax / velH;
velocityDesired.East *= vtolPathFollowerSettings.HorizontalVelMax / velH;
}
if (fabsf(velocityDesired.Down) > vtolPathFollowerSettings.VerticalVelMax) {
velocityDesired.Down *= vtolPathFollowerSettings.VerticalVelMax / fabsf(velocityDesired.Down);
if (pathDesired.Mode != PATHDESIRED_MODE_BRAKE) {
// scale velocity if it is above configured maximum
// for braking, we can not help it if initial velocity was greater
float velH = sqrtf(velocityDesired.North * velocityDesired.North + velocityDesired.East * velocityDesired.East);
if (velH > vtolPathFollowerSettings.HorizontalVelMax) {
velocityDesired.North *= vtolPathFollowerSettings.HorizontalVelMax / velH;
velocityDesired.East *= vtolPathFollowerSettings.HorizontalVelMax / velH;
}
if (fabsf(velocityDesired.Down) > vtolPathFollowerSettings.VerticalVelMax) {
velocityDesired.Down *= vtolPathFollowerSettings.VerticalVelMax / fabsf(velocityDesired.Down);
}
}
// Compute desired north command
northError = velocityDesired.North - velocityState.North;
northCommand = pid_apply(&global.PIDvel[0], northError, dT) + velocityDesired.North * vtolPathFollowerSettings.VelocityFeedforward;
// calculate the velocity errors between desired and actual
northError = velocityDesired.North - velocityState.North;
eastError = velocityDesired.East - velocityState.East;
downError = velocityDesired.Down - velocityState.Down;
// Compute desired east command
eastError = velocityDesired.East - velocityState.East;
eastCommand = pid_apply(&global.PIDvel[1], eastError, dT) + velocityDesired.East * vtolPathFollowerSettings.VelocityFeedforward;
// Compute desired down command
downError = velocityDesired.Down - velocityState.Down;
// Must flip this sign
downError = -downError;
downCommand = pid_apply(&global.PIDvel[2], downError, dT);
downError = -downError;
stabDesired.Thrust = boundf(downCommand + vtolPathFollowerSettings.ThrustLimits.Neutral, vtolPathFollowerSettings.ThrustLimits.Min, vtolPathFollowerSettings.ThrustLimits.Max);
// Compute desired commands
if (pathDesired.Mode != PATHDESIRED_MODE_BRAKE) {
northCommand = pid_apply(&global.PIDvel[0], northError, dT) + velocityDesired.North * vtolPathFollowerSettings.VelocityFeedforward;
eastCommand = pid_apply(&global.PIDvel[1], eastError, dT) + velocityDesired.East * vtolPathFollowerSettings.VelocityFeedforward;
} else {
northCommand = pid_apply(&global.BrakePIDvel[0], northError, dT) + velocityDesired.North * vtolPathFollowerSettings.BrakeVelocityFeedforward;
eastCommand = pid_apply(&global.BrakePIDvel[1], eastError, dT) + velocityDesired.East * vtolPathFollowerSettings.BrakeVelocityFeedforward;
}
downCommand = pid_apply(&global.PIDvel[2], downError, dT);
if ((vtolPathFollowerSettings.ThrustControl == VTOLPATHFOLLOWERSETTINGS_THRUSTCONTROL_MANUAL &&
flightStatus.FlightModeAssist == FLIGHTSTATUS_FLIGHTMODEASSIST_NONE) ||
(flightStatus.FlightModeAssist && flightStatus.AssistedThrottleState == FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL)) {
manual_thrust = true;
}
// if auto thrust and we have not run a correction calc check for PH and stability to then run an assessment
// note that arming into this flight mode is not allowed, so assumption here is that
// we have not landed. If GPSAssist+Manual/Cruise control thrust mode is used, a user overriding the
// altitude maintaining PID will have moved the throttle state to FLIGHTSTATUS_ASSISTEDTHROTTLESTATE_MANUAL.
// In manualcontrol.c the state will stay in manual throttle until the throttle command exceeds the vtol thrust min,
// avoiding auto-takeoffs. Therefore no need to check that here.
if (!manual_thrust && neutralThrustEst.have_correction != true) {
// Assess if position hold state running. This can be normal position hold or
// another mode with assist-hold active.
bool ph_active =
((flightStatus.FlightMode == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD &&
flightStatus.FlightModeAssist == FLIGHTSTATUS_FLIGHTMODEASSIST_NONE) ||
(flightStatus.FlightModeAssist != FLIGHTSTATUS_FLIGHTMODEASSIST_NONE &&
flightStatus.AssistedControlState == FLIGHTSTATUS_ASSISTEDCONTROLSTATE_HOLD));
bool stable = (fabsf(pathStatus.correction_direction_down) < NEUTRALTHRUST_PH_POSITIONAL_ERROR_LIMIT &&
fabsf(velocityDesired.Down) < NEUTRALTHRUST_PH_VEL_DESIRED_LIMIT &&
fabsf(velocityState.Down) < NEUTRALTHRUST_PH_VEL_STATE_LIMIT &&
fabsf(downError) < NEUTRALTHRUST_PH_VEL_ERROR_LIMIT);
if (ph_active && stable) {
if (neutralThrustEst.start_sampling) {
neutralThrustEst.count++;
// delay count for 2 seconds into hold allowing for stablisation
if (neutralThrustEst.count > NEUTRALTHRUST_START_DELAY) {
neutralThrustEst.sum += global.PIDvel[2].iAccumulator;
if (global.PIDvel[2].iAccumulator < neutralThrustEst.min) {
neutralThrustEst.min = global.PIDvel[2].iAccumulator;
}
if (global.PIDvel[2].iAccumulator > neutralThrustEst.max) {
neutralThrustEst.max = global.PIDvel[2].iAccumulator;
}
}
if (neutralThrustEst.count >= NEUTRALTHRUST_END_COUNT) {
// 6 seconds have past
// lets take an average
neutralThrustEst.average = neutralThrustEst.sum / (float)(NEUTRALTHRUST_END_COUNT - NEUTRALTHRUST_START_DELAY);
neutralThrustEst.correction = neutralThrustEst.average / 1000.0f;
global.PIDvel[2].iAccumulator -= neutralThrustEst.average;
neutralThrustEst.start_sampling = false;
neutralThrustEst.have_correction = true;
// Write a new adjustment value
// vtolSelfTuningStats.NeutralThrustOffset was incremental adjusted above
VtolSelfTuningStatsData new_vtolSelfTuningStats;
// add the average remaining i value to the
new_vtolSelfTuningStats.NeutralThrustOffset = vtolSelfTuningStats.NeutralThrustOffset + neutralThrustEst.correction;
new_vtolSelfTuningStats.NeutralThrustCorrection = neutralThrustEst.correction; // the i term thrust correction value applied
new_vtolSelfTuningStats.NeutralThrustAccumulator = global.PIDvel[2].iAccumulator; // the actual iaccumulator value after correction
new_vtolSelfTuningStats.NeutralThrustRange = neutralThrustEst.max - neutralThrustEst.min;
VtolSelfTuningStatsSet(&new_vtolSelfTuningStats);
}
} else {
// start a tick count
neutralThrustEst.start_sampling = true;
neutralThrustEst.count = 0;
neutralThrustEst.sum = 0.0f;
neutralThrustEst.max = 0.0f;
neutralThrustEst.min = 0.0f;
}
} else {
// reset sampling as we did't get 6 continuous seconds
neutralThrustEst.start_sampling = false;
}
} // else we already have a correction for this PH run
// Generally in braking the downError will be an increased altitude. We really will rely on cruisecontrol to backoff.
stabDesired.Thrust = boundf(vtolSelfTuningStats.NeutralThrustOffset + downCommand + vtolPathFollowerSettings.ThrustLimits.Neutral, vtolPathFollowerSettings.ThrustLimits.Min, vtolPathFollowerSettings.ThrustLimits.Max);
// DEBUG HACK: allow user to skew compass on purpose to see if emergency failsafe kicks in
@ -1102,6 +1362,7 @@ static int8_t updateVtolDesiredAttitude(bool yaw_attitude, float yaw_direction)
}
}
if ( // emergency flyaway detection
( // integral already at its limit
vtolPathFollowerSettings.HorizontalVelPID.ILimit - fabsf(global.PIDvel[0].iAccumulator) < 1e-6f ||
@ -1124,19 +1385,22 @@ static int8_t updateVtolDesiredAttitude(bool yaw_attitude, float yaw_direction)
// Project the north and east command signals into the pitch and roll based on yaw. For this to behave well the
// craft should move similarly for 5 deg roll versus 5 deg pitch
float maxPitch = vtolPathFollowerSettings.MaxRollPitch;
if (pathDesired.Mode == PATHDESIRED_MODE_BRAKE) {
maxPitch = vtolPathFollowerSettings.BrakeMaxPitch;
}
stabDesired.Pitch = boundf(-northCommand * cosf(DEG2RAD(attitudeState.Yaw)) +
-eastCommand * sinf(DEG2RAD(attitudeState.Yaw)),
-vtolPathFollowerSettings.MaxRollPitch, vtolPathFollowerSettings.MaxRollPitch);
-maxPitch, maxPitch);
stabDesired.Roll = boundf(-northCommand * sinf(DEG2RAD(attitudeState.Yaw)) +
eastCommand * cosf(DEG2RAD(attitudeState.Yaw)),
-vtolPathFollowerSettings.MaxRollPitch, vtolPathFollowerSettings.MaxRollPitch);
-maxPitch, maxPitch);
ManualControlCommandData manualControl;
ManualControlCommandGet(&manualControl);
if (vtolPathFollowerSettings.ThrustControl == VTOLPATHFOLLOWERSETTINGS_THRUSTCONTROL_MANUAL) {
// For now override thrust with manual control. Disable at your risk, quad goes to China.
ManualControlCommandData manualControl;
ManualControlCommandGet(&manualControl);
stabDesired.Thrust = manualControl.Thrust;
}
stabDesired.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
stabDesired.StabilizationMode.Pitch = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
@ -1145,9 +1409,51 @@ static int8_t updateVtolDesiredAttitude(bool yaw_attitude, float yaw_direction)
stabDesired.Yaw = yaw_direction;
} else {
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK;
stabDesired.Yaw = stabSettings.MaximumRate.Yaw * manualControlData.Yaw;
stabDesired.Yaw = stabSettings.MaximumRate.Yaw * manualControl.Yaw;
}
// default thrust mode to cruise control
stabDesired.StabilizationMode.Thrust = STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL;
// when flight mode assist is active but in primary-thrust mode, the thrust mode must be set to the same as per the primary mode.
if (flightStatus.FlightModeAssist == FLIGHTSTATUS_FLIGHTMODEASSIST_GPSASSIST_PRIMARYTHRUST) {
FlightModeSettingsData settings;
FlightModeSettingsGet(&settings);
FlightModeSettingsStabilization1SettingsOptions thrustMode = FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL;
switch (flightStatus.FlightMode) {
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1:
thrustMode = settings.Stabilization1Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2:
thrustMode = settings.Stabilization2Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3:
thrustMode = settings.Stabilization3Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED4:
thrustMode = settings.Stabilization4Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5:
thrustMode = settings.Stabilization5Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6:
thrustMode = settings.Stabilization6Settings.Thrust;
break;
case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
// we hard code the "GPS Assisted" PostionHold to use alt-vario which
// is a more appropriate throttle mode. "GPSAssist" adds braking
// and a better throttle management to the standard Position Hold.
thrustMode = FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEVARIO;
break;
}
stabDesired.StabilizationMode.Thrust = thrustMode;
stabDesired.Thrust = manualControl.Thrust;
} else if (manual_thrust) {
stabDesired.Thrust = manualControl.Thrust;
}
// else thrust is set by the PID controller
StabilizationDesiredSet(&stabDesired);
return result;

View File

@ -39,27 +39,33 @@
#include <receiveractivity.h>
#include <flightstatus.h>
#include <flighttelemetrystats.h>
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
#include <stabilizationsettings.h>
#endif
#include <flightmodesettings.h>
#include <systemsettings.h>
#include <taskinfo.h>
#if defined(PIOS_INCLUDE_USB_RCTX)
#include "pios_usb_rctx.h"
#endif /* PIOS_INCLUDE_USB_RCTX */
// Private constants
#if defined(PIOS_RECEIVER_STACK_SIZE)
#define STACK_SIZE_BYTES PIOS_RECEIVER_STACK_SIZE
#define STACK_SIZE_BYTES PIOS_RECEIVER_STACK_SIZE
#else
#define STACK_SIZE_BYTES 1152
#define STACK_SIZE_BYTES 1152
#endif
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3) // 3 = flight control
#define UPDATE_PERIOD_MS 20
#define THROTTLE_FAILSAFE -0.1f
#define ARMED_THRESHOLD 0.50f
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3) // 3 = flight control
#define UPDATE_PERIOD_MS 20
#define THROTTLE_FAILSAFE -0.1f
#define ARMED_THRESHOLD 0.50f
// safe band to allow a bit of calibration error or trim offset (in microseconds)
#define CONNECTION_OFFSET 250
#define CONNECTION_OFFSET 250
#define ASSISTEDCONTROL_DEADBAND_MINIMUM 0.02f // minimum value for a well bahaved Tx.
// Private types
@ -79,8 +85,12 @@ static uint32_t timeDifferenceMs(portTickType start_time, portTickType end_time)
static bool validInputRange(int16_t min, int16_t max, uint16_t value);
static void applyDeadband(float *value, float deadband);
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
static uint8_t isAssistedFlightMode(uint8_t position);
#endif
#ifdef USE_INPUT_LPF
static void applyLPF(float *value, ManualControlSettingsResponseTimeElem channel, ManualControlSettingsData *settings, float dT);
static void applyLPF(float *value, ManualControlSettingsResponseTimeElem channel, ManualControlSettingsResponseTimeData *responseTime, float deadband, float dT);
#endif
#define RCVR_ACTIVITY_MONITOR_CHANNELS_PER_GROUP 12
@ -129,6 +139,10 @@ int32_t ReceiverInitialize()
ManualControlCommandInitialize();
ReceiverActivityInitialize();
ManualControlSettingsInitialize();
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
StabilizationSettingsInitialize();
#endif
return 0;
}
@ -363,11 +377,30 @@ static void receiverTask(__attribute__((unused)) void *parameters)
cmd.FlightModeSwitchPosition = settings.FlightModeNumber - 1;
}
float deadband_checked = settings.Deadband;
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
// AssistedControl must have deadband set for pitch/roll hence
// we default to a higher value for badly behaved TXs and also enforce a minimum value
// for well behaved TXs
uint8_t assistedMode = isAssistedFlightMode(cmd.FlightModeSwitchPosition);
if (assistedMode) {
deadband_checked = settings.DeadbandAssistedControl;
if (deadband_checked < ASSISTEDCONTROL_DEADBAND_MINIMUM) {
deadband_checked = ASSISTEDCONTROL_DEADBAND_MINIMUM;
}
// If user has set settings.Deadband to a higher value...we use that.
if (deadband_checked < settings.Deadband) {
deadband_checked = settings.Deadband;
}
}
#endif // PIOS_EXCLUDE_ADVANCED_FEATURES
// Apply deadband for Roll/Pitch/Yaw stick inputs
if (settings.Deadband > 0.0f) {
applyDeadband(&cmd.Roll, settings.Deadband);
applyDeadband(&cmd.Pitch, settings.Deadband);
applyDeadband(&cmd.Yaw, settings.Deadband);
if (deadband_checked > 0.0f) {
applyDeadband(&cmd.Roll, deadband_checked);
applyDeadband(&cmd.Pitch, deadband_checked);
applyDeadband(&cmd.Yaw, deadband_checked);
}
#ifdef USE_INPUT_LPF
// Apply Low Pass Filter to input channels, time delta between calls in ms
@ -377,9 +410,9 @@ static void receiverTask(__attribute__((unused)) void *parameters)
(float)UPDATE_PERIOD_MS;
lastSysTimeLPF = thisSysTime;
applyLPF(&cmd.Roll, MANUALCONTROLSETTINGS_RESPONSETIME_ROLL, &settings, dT);
applyLPF(&cmd.Pitch, MANUALCONTROLSETTINGS_RESPONSETIME_PITCH, &settings, dT);
applyLPF(&cmd.Yaw, MANUALCONTROLSETTINGS_RESPONSETIME_YAW, &settings, dT);
applyLPF(&cmd.Roll, MANUALCONTROLSETTINGS_RESPONSETIME_ROLL, &settings.ResponseTime, deadband_checked, dT);
applyLPF(&cmd.Pitch, MANUALCONTROLSETTINGS_RESPONSETIME_PITCH, &settings.ResponseTime, deadband_checked, dT);
applyLPF(&cmd.Yaw, MANUALCONTROLSETTINGS_RESPONSETIME_YAW, &settings.ResponseTime, deadband_checked, dT);
#endif // USE_INPUT_LPF
if (cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != (uint16_t)PIOS_RCVR_INVALID
&& cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != (uint16_t)PIOS_RCVR_NODRIVER
@ -389,7 +422,7 @@ static void receiverTask(__attribute__((unused)) void *parameters)
applyDeadband(&cmd.Collective, settings.Deadband);
}
#ifdef USE_INPUT_LPF
applyLPF(&cmd.Collective, MANUALCONTROLSETTINGS_RESPONSETIME_COLLECTIVE, &settings, dT);
applyLPF(&cmd.Collective, MANUALCONTROLSETTINGS_RESPONSETIME_COLLECTIVE, &settings.ResponseTime, settings.Deadband, dT);
#endif // USE_INPUT_LPF
}
@ -409,7 +442,7 @@ static void receiverTask(__attribute__((unused)) void *parameters)
if (settings.ChannelGroups.Accessory0 != MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) {
accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY0];
#ifdef USE_INPUT_LPF
applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY0, &settings, dT);
applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY0, &settings.ResponseTime, settings.Deadband, dT);
#endif
if (AccessoryDesiredInstSet(0, &accessory) != 0) {
AlarmsSet(SYSTEMALARMS_ALARM_RECEIVER, SYSTEMALARMS_ALARM_WARNING);
@ -419,7 +452,7 @@ static void receiverTask(__attribute__((unused)) void *parameters)
if (settings.ChannelGroups.Accessory1 != MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) {
accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY1];
#ifdef USE_INPUT_LPF
applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY1, &settings, dT);
applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY1, &settings.ResponseTime, settings.Deadband, dT);
#endif
if (AccessoryDesiredInstSet(1, &accessory) != 0) {
AlarmsSet(SYSTEMALARMS_ALARM_RECEIVER, SYSTEMALARMS_ALARM_WARNING);
@ -429,7 +462,7 @@ static void receiverTask(__attribute__((unused)) void *parameters)
if (settings.ChannelGroups.Accessory2 != MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) {
accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY2];
#ifdef USE_INPUT_LPF
applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY2, &settings, dT);
applyLPF(&accessory.AccessoryVal, MANUALCONTROLSETTINGS_RESPONSETIME_ACCESSORY2, &settings.ResponseTime, settings.Deadband, dT);
#endif
if (AccessoryDesiredInstSet(2, &accessory) != 0) {
@ -440,6 +473,8 @@ static void receiverTask(__attribute__((unused)) void *parameters)
// Update cmd object
ManualControlCommandSet(&cmd);
#if defined(PIOS_INCLUDE_USB_RCTX)
if (pios_usb_rctx_id) {
PIOS_USB_RCTX_Update(pios_usb_rctx_id,
@ -658,16 +693,42 @@ static void applyDeadband(float *value, float deadband)
/**
* @brief Apply Low Pass Filter to Throttle/Roll/Pitch/Yaw or Accessory channel
*/
static void applyLPF(float *value, ManualControlSettingsResponseTimeElem channel, ManualControlSettingsData *settings, float dT)
static void applyLPF(float *value, ManualControlSettingsResponseTimeElem channel, ManualControlSettingsResponseTimeData *responseTime, float deadband, float dT)
{
if (ManualControlSettingsResponseTimeToArray(settings->ResponseTime)[channel]) {
float rt = (float)ManualControlSettingsResponseTimeToArray(settings->ResponseTime)[channel];
float rt = (float)ManualControlSettingsResponseTimeToArray((*responseTime))[channel];
if (rt > 0.0f) {
inputFiltered[channel] = ((rt * inputFiltered[channel]) + (dT * (*value))) / (rt + dT);
// avoid a long tail of non-zero data. if we have deadband, once the filtered result reduces to 1/10th
// of deadband revert to 0. We downstream rely on this to know when sticks are centered.
if (deadband > 0.0f && fabsf(inputFiltered[channel]) < deadband / 10.0f) {
inputFiltered[channel] = 0.0f;
}
*value = inputFiltered[channel];
}
}
#endif // USE_INPUT_LPF
/**
* Check and set modes for gps assisted stablised flight modes
*/
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
static uint8_t isAssistedFlightMode(uint8_t position)
{
uint8_t isAssistedFlag = STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NONE;
uint8_t FlightModeAssistMap[STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NUMELEM];
StabilizationSettingsFlightModeAssistMapGet(FlightModeAssistMap);
if (position < STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NUMELEM) {
isAssistedFlag = FlightModeAssistMap[position];
}
return isAssistedFlag;
}
#endif
/**
* @}
* @}

View File

@ -558,7 +558,7 @@ void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr)
/**
* Sets the range and number of channels to use for the radio.
* The channels are 0 to 255 divided across the 430-440 MHz range.
* The channels are 0 to 250 divided across the 430-440 MHz range.
* The number of channels configured will be spread across the selected channel range.
* The channel spacing is 10MHz / 250 = 40kHz
*
@ -1618,7 +1618,7 @@ static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev,
{
// Set the frequency channels to start at 430MHz
uint32_t frequency_hz = RFM22B_NOMINAL_CARRIER_FREQUENCY;
// The step size is 10MHz / 250 channels = 40khz, and the step size is specified in 10khz increments.
// The step size is 10MHz / 250 = 40khz, and the step size is specified in 10khz increments.
uint8_t freq_hop_step_size = 4;
// holds the hbsel (1 or 2)

View File

@ -213,20 +213,21 @@ static int PIOS_DSM_UnrollChannels(struct pios_dsm_dev *dsm_dev)
/* extract and save the channel value */
uint8_t channel_num = (word >> resolution) & 0x0f;
if (channel_num < PIOS_DSM_NUM_INPUTS) {
if (channel_log & (1 << channel_num)) {
/* Found duplicate. This should happen when in 11 bit */
/* mode and the data is 10 bits */
if (resolution == 10)
if (resolution == 10) {
return -1;
}
resolution = 10;
return PIOS_DSM_UnrollChannels(dsm_dev);
}
if ((channel_log & 0xFF) == 0x55) {
/* This pattern indicates 10 bit pattern */
if (resolution == 11)
if (resolution == 11) {
return -1;
}
resolution = 11;
return PIOS_DSM_UnrollChannels(dsm_dev);
}

View File

@ -215,20 +215,21 @@ static int PIOS_DSM_UnrollChannels(struct pios_dsm_dev *dsm_dev)
/* extract and save the channel value */
uint8_t channel_num = (word >> resolution) & 0x0f;
if (channel_num < PIOS_DSM_NUM_INPUTS) {
if (channel_log & (1 << channel_num)) {
/* Found duplicate. This should happen when in 11 bit */
/* mode and the data is 10 bits */
if (resolution == 10)
if (resolution == 10) {
return -1;
}
resolution = 10;
return PIOS_DSM_UnrollChannels(dsm_dev);
}
if ((channel_log & 0xFF) == 0x55) {
/* This pattern indicates 10 bit pattern */
if (resolution == 11)
if (resolution == 11) {
return -1;
}
resolution = 11;
return PIOS_DSM_UnrollChannels(dsm_dev);
}

View File

@ -74,7 +74,7 @@ static void genericTIM_OCxPreloadConfig(TIM_TypeDef *TIMx, uint16_t TIM_OCPreloa
},
},
....
[HWSETTINGS_WS2811LED_OUT_FLEXIPIN4] = {
[HWSETTINGS_WS2811LED_OUT_FLEXIIOPIN4] = {
.gpio = GPIOB,
.gpioInit = {
.GPIO_Pin = GPIO_Pin_13,

View File

@ -19,6 +19,7 @@
# These are the UAVObjects supposed to be build as part of the OpenPilot target
# (all architectures)
UAVOBJSRCFILENAMES =
UAVOBJSRCFILENAMES += vtolselftuningstats
UAVOBJSRCFILENAMES += accelgyrosettings
UAVOBJSRCFILENAMES += accessorydesired
UAVOBJSRCFILENAMES += actuatorcommand
@ -76,6 +77,7 @@ UAVOBJSRCFILENAMES += pathaction
UAVOBJSRCFILENAMES += pathdesired
UAVOBJSRCFILENAMES += pathplan
UAVOBJSRCFILENAMES += pathstatus
UAVOBJSRCFILENAMES += pathsummary
UAVOBJSRCFILENAMES += positionstate
UAVOBJSRCFILENAMES += ratedesired
UAVOBJSRCFILENAMES += ekfconfiguration

View File

@ -2020,72 +2020,72 @@ void DMA2_Stream1_IRQHandler(void) __attribute__((alias("PIOS_WS2811_irq_handler
// this will not clash with PWM in or servo output as
// pins will be reconfigured as _OUT so the alternate function is disabled.
const struct pios_ws2811_pin_cfg pios_ws2811_pin_cfg[] = {
[HWSETTINGS_WS2811LED_OUT_SERVOOUT1] = {
[HWSETTINGS_WS2811LED_OUT_SERVOOUT1] = {
.gpio = GPIOB,
.gpioInit = {
.gpioInit = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_SERVOOUT2] = {
[HWSETTINGS_WS2811LED_OUT_SERVOOUT2] = {
.gpio = GPIOB,
.gpioInit = {
.gpioInit = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_SERVOOUT3] = {
[HWSETTINGS_WS2811LED_OUT_SERVOOUT3] = {
.gpio = GPIOA,
.gpioInit = {
.gpioInit = {
.GPIO_Pin = GPIO_Pin_3,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_SERVOOUT4] = {
[HWSETTINGS_WS2811LED_OUT_SERVOOUT4] = {
.gpio = GPIOA,
.gpioInit = {
.gpioInit = {
.GPIO_Pin = GPIO_Pin_2,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_SERVOOUT5] = {
[HWSETTINGS_WS2811LED_OUT_SERVOOUT5] = {
.gpio = GPIOA,
.gpioInit = {
.gpioInit = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_SERVOOUT6] = {
[HWSETTINGS_WS2811LED_OUT_SERVOOUT6] = {
.gpio = GPIOA,
.gpioInit = {
.gpioInit = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_FLEXIPIN3] = {
[HWSETTINGS_WS2811LED_OUT_FLEXIIOPIN3] = {
.gpio = GPIOB,
.gpioInit = {
.gpioInit = {
.GPIO_Pin = GPIO_Pin_12,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
[HWSETTINGS_WS2811LED_OUT_FLEXIPIN4] = {
[HWSETTINGS_WS2811LED_OUT_FLEXIIOPIN4] = {
.gpio = GPIOB,
.gpioInit = {
.gpioInit = {
.GPIO_Pin = GPIO_Pin_13,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,

View File

@ -19,6 +19,7 @@
# These are the UAVObjects supposed to be build as part of the OpenPilot target
# (all architectures)
UAVOBJSRCFILENAMES =
UAVOBJSRCFILENAMES += vtolselftuningstats
UAVOBJSRCFILENAMES += accelgyrosettings
UAVOBJSRCFILENAMES += accessorydesired
UAVOBJSRCFILENAMES += actuatorcommand
@ -76,6 +77,7 @@ UAVOBJSRCFILENAMES += pathaction
UAVOBJSRCFILENAMES += pathdesired
UAVOBJSRCFILENAMES += pathplan
UAVOBJSRCFILENAMES += pathstatus
UAVOBJSRCFILENAMES += pathsummary
UAVOBJSRCFILENAMES += positionstate
UAVOBJSRCFILENAMES += ratedesired
UAVOBJSRCFILENAMES += ekfconfiguration

View File

@ -19,6 +19,7 @@
# These are the UAVObjects supposed to be build as part of the OpenPilot target
# (all architectures)
UAVOBJSRCFILENAMES =
UAVOBJSRCFILENAMES += vtolselftuningstats
UAVOBJSRCFILENAMES += accelgyrosettings
UAVOBJSRCFILENAMES += accessorydesired
UAVOBJSRCFILENAMES += actuatorcommand
@ -76,6 +77,7 @@ UAVOBJSRCFILENAMES += pathaction
UAVOBJSRCFILENAMES += pathdesired
UAVOBJSRCFILENAMES += pathplan
UAVOBJSRCFILENAMES += pathstatus
UAVOBJSRCFILENAMES += pathsummary
UAVOBJSRCFILENAMES += positionstate
UAVOBJSRCFILENAMES += ratedesired
UAVOBJSRCFILENAMES += ekfconfiguration

View File

@ -24,6 +24,7 @@
# (all architectures)
UAVOBJSRCFILENAMES =
UAVOBJSRCFILENAMES += vtolselftuningstats
UAVOBJSRCFILENAMES += accessorydesired
UAVOBJSRCFILENAMES += actuatorcommand
UAVOBJSRCFILENAMES += actuatordesired
@ -77,6 +78,7 @@ UAVOBJSRCFILENAMES += pathaction
UAVOBJSRCFILENAMES += pathdesired
UAVOBJSRCFILENAMES += pathplan
UAVOBJSRCFILENAMES += pathstatus
UAVOBJSRCFILENAMES += pathsummary
UAVOBJSRCFILENAMES += positionstate
UAVOBJSRCFILENAMES += ratedesired
UAVOBJSRCFILENAMES += revocalibration

View File

@ -96,7 +96,15 @@ macx {
copydata = 1
copyqt = 1
} else {
GCS_LIBRARY_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/openpilotgcs
GCS_PLUGIN_PATH = $$GCS_LIBRARY_PATH/plugins
GCS_LIBEXEC_PATH = $$GCS_APP_PATH # FIXME
GCS_DATA_PATH = $$GCS_BUILD_TREE/share/openpilotgcs
GCS_DATA_BASENAME = share/openpilotgcs
GCS_DOC_PATH = $$GCS_BUILD_TREE/share/doc
!isEqual(GCS_SOURCE_TREE, $$GCS_BUILD_TREE):copydata = 1
win32 {
SDL_DIR = $$(SDL_DIR)
isEmpty(SDL_DIR):SDL_DIR = $${TOOLS_DIR}/SDL-1.2.15
@ -112,26 +120,18 @@ macx {
copyqt = $$copydata
} else {
GCS_APP_TARGET = openpilotgcs
GCS_QT_LIBRARY_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/qt5
GCS_QT_PLUGINS_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/qt5/plugins
GCS_QT_QML_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/qt5/qml
GCS_QT_BASEPATH = $$GCS_LIBRARY_PATH/qt5
GCS_QT_LIBRARY_PATH = $$GCS_QT_BASEPATH/lib
GCS_QT_PLUGINS_PATH = $$GCS_QT_BASEPATH/plugins
GCS_QT_QML_PATH = $$GCS_QT_BASEPATH/qml
QT_INSTALL_DIR = $$clean_path($$[QT_INSTALL_LIBS]/../../../..)
equals(QT_INSTALL_DIR, $$TOOLS_DIR) {
copyqt = 1
} else {
copyqt = 0
copyqt = 0
}
FORCE_COPY_QT = $$(FORCE_COPY_QT)
!isEmpty(FORCE_COPY_QT):copyqt = 1
}
GCS_LIBRARY_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/openpilotgcs
GCS_PLUGIN_PATH = $$GCS_LIBRARY_PATH/plugins
GCS_LIBEXEC_PATH = $$GCS_APP_PATH # FIXME
GCS_DATA_PATH = $$GCS_BUILD_TREE/share/openpilotgcs
GCS_DATA_BASENAME = share/openpilotgcs
GCS_DOC_PATH = $$GCS_BUILD_TREE/share/doc
}

View File

@ -11,8 +11,8 @@ QT_VERSION = $$split(QT_VERSION, ".")
QT_VER_MAJ = $$member(QT_VERSION, 0)
QT_VER_MIN = $$member(QT_VERSION, 1)
lessThan(QT_VER_MAJ, 5) | lessThan(QT_VER_MIN, 4) {
error(OpenPilot GCS requires Qt 5.4.0 or newer but Qt $$[QT_VERSION] was detected.)
lessThan(QT_VER_MAJ, 5) | lessThan(QT_VER_MIN, 2) {
error(OpenPilot GCS requires Qt 5.2.0 or newer but Qt $$[QT_VERSION] was detected.)
}
macx {

View File

@ -45,7 +45,7 @@ Item {
text: altitude_scale.topNumber - index
color: "white"
font.pixelSize: parent.height / 3
font.family: "Arial"
font.family: pt_bold.name
anchors.horizontalCenter: parent.horizontalCenter
anchors.verticalCenter: parent.top
@ -100,7 +100,7 @@ Item {
text: " " +altitude.toFixed(1)
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: parent.height * 0.35
weight: Font.DemiBold
}
@ -125,7 +125,7 @@ Item {
text: qmlWidget.altitudeUnit
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: parent.height * 0.6
weight: Font.DemiBold
}

View File

@ -88,7 +88,7 @@ Item {
text: Math.floor(AttitudeState.Yaw).toFixed()
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: parent.height * 1.2
}
anchors.centerIn: parent

View File

@ -105,7 +105,7 @@ Item {
text: ["NO GPS", "NO FIX", "FIX 2D", "FIX 3D"][GPSPositionSensor.Status]
anchors.centerIn: parent
font.pixelSize: Math.floor(parent.height*1.3)
font.family: "Arial"
font.family: pt_bold.name
font.weight: Font.DemiBold
color: "white"
}
@ -138,7 +138,7 @@ Item {
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.5)
weight: Font.DemiBold
}
@ -159,7 +159,7 @@ Item {
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.5)
weight: Font.DemiBold
}
@ -182,7 +182,7 @@ Item {
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.5)
weight: Font.DemiBold
}
@ -208,7 +208,7 @@ Item {
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.5)
weight: Font.DemiBold
}
@ -229,7 +229,7 @@ Item {
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.5)
weight: Font.DemiBold
}
@ -251,7 +251,7 @@ Item {
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.5)
weight: Font.DemiBold
}
@ -307,7 +307,7 @@ Item {
anchors.centerIn: parent
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.6)
weight: Font.DemiBold
}
@ -334,7 +334,7 @@ Item {
anchors.centerIn: parent
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.6)
weight: Font.DemiBold
}
@ -368,7 +368,7 @@ Item {
anchors.centerIn: parent
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.6)
weight: Font.DemiBold
}
@ -405,7 +405,7 @@ Item {
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1)
weight: Font.DemiBold
}
@ -471,7 +471,7 @@ Item {
anchors.centerIn: parent
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: parent.height * 1.2
}
}
@ -502,7 +502,7 @@ Item {
anchors.centerIn: parent
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: parent.height * 1.2
}
}
@ -533,7 +533,7 @@ Item {
anchors.centerIn: parent
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: parent.height * 1.2
}
}

View File

@ -69,7 +69,10 @@ Item {
property real smeter_angle
property real memory_free : SystemStats.HeapRemaining > 1024 ? SystemStats.HeapRemaining / 1024 : SystemStats.HeapRemaining
property real memory_free : SystemStats.HeapRemaining > 1024 ? SystemStats.HeapRemaining / 1024 : SystemStats.HeapRemaining
// Needed to get correctly int8 value
property int cpuTemp : SystemStats.CPUTemp
// Needed to get correctly int8 value, reset value (-127) on disconnect
property int oplm0_db: telemetry_link == 1 ? OPLinkStatus.PairSignalStrengths_0 : -127
@ -404,7 +407,7 @@ Item {
anchors.centerIn: parent
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.6)
}
}
@ -445,7 +448,7 @@ Item {
anchors.centerIn: parent
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.6)
}
}
@ -490,7 +493,7 @@ Item {
anchors.centerIn: parent
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.6)
}
}
@ -536,7 +539,7 @@ Item {
anchors.centerIn: parent
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.6)
}
}
@ -809,7 +812,7 @@ Item {
anchors.centerIn: parent
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.4)
weight: Font.DemiBold
capitalization: Font.AllUppercase
@ -895,7 +898,7 @@ Item {
anchors.right: parent.right
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.4)
weight: Font.DemiBold
}
@ -922,13 +925,13 @@ Item {
}
Text {
// CC3D hack, Cputemp not working
text: SystemStats.CPULoad+"% - "+
[String(SystemStats.CPUTemp).charCodeAt(0) == "64" ? "??" : String(SystemStats.CPUTemp).charCodeAt(0)] +"°C"
// Coptercontrol detect with mem free : Only display Cpu load, no temperature available.
text: SystemStats.CPULoad+"%"+
[SystemStats.HeapRemaining < 3000 ? "" : " | "+cpuTemp+"°C"]
anchors.right: parent.right
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.4)
weight: Font.DemiBold
}
@ -959,7 +962,7 @@ Item {
anchors.right: parent.right
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.4)
weight: Font.DemiBold
}
@ -986,12 +989,12 @@ Item {
}
Text {
text: ["None", "Complementary", "CompMag", "Comp+Mag+GPS", "EKFIndoor", "EKFOutdoor"][RevoSettings.FusionAlgorithm]
text: ["None", "Basic (No Nav)", "CompMag", "Comp+Mag+GPS", "EKFIndoor", "GPS Nav (INS13)"][RevoSettings.FusionAlgorithm]
anchors.right: parent.right
color: "white"
font {
family: "Arial"
pixelSize: Math.floor(parent.height * 1.2)
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.35)
weight: Font.DemiBold
}
}
@ -1021,7 +1024,7 @@ Item {
anchors.right: parent.right
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.4)
weight: Font.DemiBold
}
@ -1052,7 +1055,7 @@ Item {
anchors.right: parent.right
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 1.4)
weight: Font.DemiBold
}

View File

@ -24,6 +24,11 @@ Rectangle {
Item {
id: sceneItem
FontLoader {
id: pt_bold
source: "qrc:/pfdqml/fonts/PTS75F.ttf"
}
width: Math.floor((parent.paintedHeight * 1.32) - (parent.paintedHeight * 0.013))
height: Math.floor(parent.paintedHeight - parent.paintedHeight * 0.02)
property variant viewportSize : Qt.size(width, height)

View File

@ -22,7 +22,7 @@ Item {
id: telemetry_rate
text: GCSTelemetryStats.TxDataRate.toFixed()+"/"+GCSTelemetryStats.RxDataRate.toFixed()
color: "white"
font.family: "Arial"
font.family: pt_bold.name
font.pixelSize: telemetry_status.height * 0.75
anchors.top: telemetry_status.bottom
@ -33,7 +33,7 @@ Item {
id: gps_text
text: "GPS: " + GPSPositionSensor.Satellites + "\nPDP: " + Math.round(GPSPositionSensor.PDOP*10)/10
color: "white"
font.family: "Arial"
font.family: pt_bold.name
font.pixelSize: telemetry_status.height * 0.75
visible: GPSPositionSensor.Satellites > 0
@ -52,7 +52,7 @@ Item {
color: "white"
font.family: "Arial"
font.family: pt_bold.name
//I think it should be pixel size,
//but making it more consistent with C++ version instead

View File

@ -49,7 +49,7 @@ Item {
visible: speed_scale.topNumber - index >= 0
font.pixelSize: parent.height / 3
font.family: "Arial"
font.family: pt_bold.name
anchors.horizontalCenter: parent.horizontalCenter
anchors.verticalCenter: parent.top
@ -90,7 +90,7 @@ Item {
text: sceneItem.groundSpeed.toFixed(1)+" "
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: parent.height * 0.35
weight: Font.DemiBold
}
@ -115,7 +115,7 @@ Item {
text: qmlWidget.speedUnit
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: parent.height * 0.6
weight: Font.DemiBold
}

View File

@ -86,7 +86,7 @@ Item {
text: qmlWidget.altitudeUnit == "m" ? "m/s" : "ft/s"
color: "cyan"
font {
family: "Arial"
family: pt_bold.name
pixelSize: parent.height * 1.7
weight: Font.DemiBold
}

View File

@ -2,19 +2,20 @@ import QtQuick 2.0
Item {
id: warnings
property variant sceneSize
// Uninitialised, OK, Warning, Error, Critical
property variant statusColors : ["gray", "green", "red", "red", "red"]
// DisArmed , Arming, Armed
property variant armColors : ["gray", "orange", "green"]
// All 'manual modes' are green, 'assisted' modes in cyan
// "MANUAL","STAB 1","STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6", "AUTOTUNE",
// "POS HOLD", "POS VFPV", "POS VLOS", "POS VNSEW", "RTB", "LAND", "PATHPLANNER", "POI", "AUTOCRUISE"
// "MANUAL","STAB 1","STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6",
// "POS HOLD", "COURSE LOCK", "POS ROAM", "HOME LEASH", "ABS POS", "RTB", "LAND", "PATHPLANNER", "POI", "AUTOCRUISE"
property variant flightmodeColors : ["gray", "green", "green", "green", "green", "green", "green", "red",
"cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan"]
property variant flightmodeColors : ["gray", "green", "green", "green", "green", "green", "green",
"cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan"]
// Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Acro+,Rattitude,
// AltitudeHold,AltitudeVario,CruiseControl + Auto mode (VTOL/Wing pathfollower)
@ -26,9 +27,9 @@ Item {
// SystemSettings.AirframeType 3 - 18 : VtolPathFollower, check ThrustControl
property var thrust_mode: FlightStatus.FlightMode < 7 ? StabilizationDesired.StabilizationMode_Thrust :
FlightStatus.FlightMode > 7 && SystemSettings.AirframeType > 2 && SystemSettings.AirframeType < 19
FlightStatus.FlightMode > 6 && SystemSettings.AirframeType > 2 && SystemSettings.AirframeType < 19
&& VtolPathFollowerSettings.ThrustControl == 1 ? 11 :
FlightStatus.FlightMode > 7 && SystemSettings.AirframeType < 3 ? 11: 0
FlightStatus.FlightMode > 6 && SystemSettings.AirframeType < 3 ? 11: 0
property real flight_time: Math.round(SystemStats.FlightTime / 1000)
@ -70,7 +71,7 @@ Item {
anchors.centerIn: parent
text: formatTime(time_h) + ":" + formatTime(time_m) + ":" + formatTime(time_s)
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.8)
weight: Font.DemiBold
}
@ -95,7 +96,7 @@ Item {
anchors.centerIn: parent
text: ["DISARMED","ARMING","ARMED"][FlightStatus.Armed]
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.74)
weight: Font.DemiBold
}
@ -120,7 +121,7 @@ Item {
anchors.centerIn: parent
text: "RC INPUT"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.74)
weight: Font.DemiBold
}
@ -152,7 +153,7 @@ Item {
text: "MASTER CAUTION"
color: "white"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.74)
weight: Font.DemiBold
}
@ -177,7 +178,7 @@ Item {
anchors.centerIn: parent
text: "AUTOPILOT"
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.74)
weight: Font.DemiBold
}
@ -200,10 +201,10 @@ Item {
Text {
anchors.centerIn: parent
text: ["MANUAL","STAB 1","STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6", "AUTOTUNE", "POS HOLD", "POS VFPV",
"POS VLOS", "POS VNSEW", "RTB", "LAND", "PATHPLAN", "POI", "AUTOCRUISE"][FlightStatus.FlightMode]
text: ["MANUAL","STAB 1","STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6", "POS HOLD", "COURSELOCK",
"POS ROAM", "HOME LEASH", "ABS POS", "RTB", "LAND", "PATHPLAN", "POI", "AUTOCRUISE"][FlightStatus.FlightMode]
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.74)
weight: Font.DemiBold
}
@ -232,7 +233,7 @@ Item {
text: ["MANUAL"," "," ", " ", " ", " ", " ", " ",
"ALT HOLD", "ALT VARIO", "CRUISECTRL", "AUTO"][thrust_mode.toString()]
font {
family: "Arial"
family: pt_bold.name
pixelSize: Math.floor(parent.height * 0.74)
weight: Font.DemiBold
}

View File

@ -4393,8 +4393,7 @@ p, li { white-space: pre-wrap; }
<message>
<location line="+30"/>
<source>http://wiki.openpilot.org/x/OQBj</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/hoBqAQ</translation>
<translation></translation>
</message>
<message>
<location line="+8"/>
@ -4508,7 +4507,12 @@ p, li { white-space: pre-wrap; }
<translation> Les paramètres importés ne sont pas compatibles avec ce plugin et ne seront pas importés !</translation>
</message>
<message>
<location line="-12"/>
<location line="+7"/>
<source> Unknown compatibility level: %1</source>
<translation> Niveau de compatibilité inconnu : %1</translation>
</message>
<message>
<location line="-19"/>
<source>WARNING: </source>
<translation>ATTENTION : </translation>
</message>
@ -4518,9 +4522,8 @@ p, li { white-space: pre-wrap; }
<translation>ERREUR : </translation>
</message>
<message>
<location line="+13"/>
<source> Unknown compatibility level: </source>
<translation> Niveau de compatibilité inconnu : </translation>
<translation type="vanished"> Niveau de compatibilité inconnu : </translation>
</message>
</context>
<context>
@ -5233,8 +5236,7 @@ valeur.</translation>
<message>
<location/>
<source>url:http://wiki.openpilot.org/display/Doc/Camera+Stabilization+Configuration</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>url:http://wiki.openpilot.org/x/UoHWAQ</translation>
<translation></translation>
</message>
<message>
<location/>
@ -6180,9 +6182,8 @@ p, li { white-space: pre-wrap; }
<translation>Options de Configuration et Calibration</translation>
</message>
<message>
<location/>
<source>Manual Calibration</source>
<translation>Calibration Manuelle</translation>
<translation type="vanished">Calibration Manuelle</translation>
</message>
<message>
<location/>
@ -6489,6 +6490,37 @@ Applique et Enregistre tous les paramètres sur la SD</translation>
<source>Start Transmitter Setup Wizard</source>
<translation>Démarrer l&apos;Assistant Configuration Émetteur</translation>
</message>
<message>
<location/>
<source>Assisted Control stick deadband </source>
<translation type="unfinished">Zone morte des manches - Pilotage assisté </translation>
</message>
<message>
<location/>
<source>Assisted Control stick deadband in percents of full range (2-12) for use with GPSAssist. This can not be disabled.</source>
<translation type="unfinished">Zone morte des manches du pilotage assisté en pourcentage du débattement maximum (2-12) pour utiliser GPSAssist. Ne peut être désactivé.</translation>
</message>
<message>
<location/>
<source>Start Manual Calibration</source>
<translation>Démarrer Calibration Manuelle</translation>
</message>
<message>
<location/>
<source>Assisted Control</source>
<translation type="unfinished">Pilotage Assisté</translation>
</message>
<message>
<location/>
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation type="unfinished">&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Les options du pilotage assisté améliorent le mode de vol courant. GPSAssist ajoute le freinage/maintien en position à la Stabilisation et PositionHold.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location/>
<source>fieldname:FlightModeAssistMap</source>
<translatorcomment>Do not translate !</translatorcomment>
<translation></translation>
</message>
</context>
<context>
<name>MixerCurve</name>
@ -7079,8 +7111,7 @@ Une valeur de 0.00 désactive le filtre.</translation>
<message>
<location/>
<source>url:http://wiki.openpilot.org/display/Doc/Revolution+Manual+Sensor+Calibration</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>url:http://wiki.openpilot.org/x/FQWJAQ</translation>
<translation></translation>
</message>
<message>
<location/>
@ -7616,8 +7647,7 @@ value as the Kp.</source>
<message>
<location/>
<source>url:http://wiki.openpilot.org/x/DAO9</source>
<translatorcomment>Wiki FR</translatorcomment>
<translation>url:http://wiki.openpilot.org/x/d4BqAQ</translation>
<translation></translation>
</message>
<message>
<location/>
@ -8583,8 +8613,7 @@ uniquement lorsque le système est armé, sans désactiver le module.</translati
<message>
<location/>
<source>url:http://wiki.openpilot.org/x/DACiAQ</source>
<translatorcomment>Wiki FR</translatorcomment>
<translation>url:http://wiki.openpilot.org/x/N4DWAQ</translation>
<translation></translation>
</message>
<message>
<location/>
@ -9098,7 +9127,7 @@ les données en cache</translation>
<translation>Diagramme de Connexion</translation>
</message>
<message>
<location line="+200"/>
<location line="+213"/>
<source>Save File</source>
<translation>Enregistrer Fichier</translation>
</message>
@ -9323,6 +9352,16 @@ Veuillez sélectionner la configuration de voilure fixe désirée ci-dessous :</
<source>This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet supported. Setup should include only two elevons, and should explicitly not include a rudder.</source>
<translation>Cette configuration concerne les ailes volantes, la dérive n&apos;est pas encore supportée actuellement. La configuration s&apos;applique à deux servos d&apos;élevons, sans dérive.</translation>
</message>
<message>
<location line="+5"/>
<source>Vtail</source>
<translation type="unfinished">Vtail</translation>
</message>
<message>
<location line="+1"/>
<source>This setup expects a traditional glider airframe using two independent aileron servos on their own channel (not connected by Y adapter) plus Vtail mixing elevator/rudder.</source>
<translation>Cette configuration concerne un planeur classique utilisant deux servos d&apos;ailerons indépendants ayant leur propre branchement (pas connectés avec un adaptateur en Y) plus un empenage en avec mixage profondeur/direction.</translation>
</message>
</context>
<context>
<name>HeliPage</name>
@ -9435,17 +9474,15 @@ p, li { white-space: pre-wrap; }
<translation>Le Quadricoptère (+) utilise quatre moteurs et il est similaire au Quadricoptère X mais la direction de déplacement est décalée de 45 degrés. Les moteurs avant et arrière tournent dans le sens horaire et les moteurs gauche et droit tournent dans le sens antihoraire. Cette configuration a é l&apos;une des premières à être utilisée et est encore utilisée pour le vol sportif. Cette agencement n&apos;est pas bien adapté pour que FPV car le moteur de devant a tendance à être dans le champ de vision de la caméra.</translation>
</message>
<message>
<location line="+7"/>
<source>Quadcopter H</source>
<translation>Quadricoptère H</translation>
<translation type="vanished">Quadricoptère H</translation>
</message>
<message>
<location line="+1"/>
<source>Quadcopter H, Blackout miniH</source>
<translation>Quadricoptère H, blackout miniH</translation>
<translation type="vanished">Quadricoptère H, blackout miniH</translation>
</message>
<message>
<location line="+4"/>
<location line="+7"/>
<source>Hexacopter</source>
<translation>Hexacoptère</translation>
</message>
@ -9480,7 +9517,7 @@ p, li { white-space: pre-wrap; }
<translation>Hexacoptère X</translation>
</message>
<message>
<location line="-38"/>
<location line="-33"/>
<source>OpenPilot Multirotor Configuration</source>
<translation>Configuration Multirotor OpenPilot</translation>
</message>
@ -9494,7 +9531,7 @@ Please select the type of multirotor you want to create a configuration for belo
Veuillez sélectionner le type de multirotor désiré pour la configuration ci-dessous :</translation>
</message>
<message>
<location line="+42"/>
<location line="+37"/>
<source>Hexacopter H</source>
<translation>Hexacoptère H</translation>
</message>
@ -9527,7 +9564,7 @@ Veuillez sélectionner le type de multirotor désiré pour la configuration ci-d
</message>
<message>
<location/>
<location filename="../../../src/plugins/setupwizard/pages/outputcalibrationpage.cpp" line="+375"/>
<location filename="../../../src/plugins/setupwizard/pages/outputcalibrationpage.cpp" line="+415"/>
<location line="+90"/>
<source>Start</source>
<translation>Démarrer</translation>
@ -9760,6 +9797,50 @@ p, li { white-space: pre-wrap; }
<source>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p align=&quot;center&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:12pt; font-weight:600;&quot;&gt;The Surface Vehicle section of the OpenPilot Setup Wizard is not yet implemented&lt;/span&gt;&lt;br/&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</source>
<translation>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p align=&quot;center&quot;&gt;&lt;span style=&quot; font-family:&apos;MS Shell Dlg 2&apos;; font-size:12pt; font-weight:600;&quot;&gt;La partie Véhicule roulant de l&apos;Assistant de Configuration OpenPilot n&apos;est pas encore implémentée&lt;/span&gt;&lt;br/&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</translation>
</message>
<message>
<location filename="../../../src/plugins/setupwizard/pages/surfacepage.cpp" line="+51"/>
<source>OpenPilot Ground Vehicle Configuration</source>
<translation>Configuration Véhicule Terrestre OpenPilot</translation>
</message>
<message>
<location line="+1"/>
<source>This part of the wizard will set up the OpenPilot controller for use with a ground vehicle utilizing servos. The wizard supports the most common types of ground vehicle, other variants can be configured by using custom configuration options in the Configuration plugin in the GCS.
Please select the type of ground vehicle you want to create a configuration for below:</source>
<translation>Cette partie de l&apos;assistant va permettre le configuration du contrôleur OpenPilot pour fonctionner avec des véhicules terrestres utilisant plusieurs moteurs/servos. L&apos;assistant supporte les types de configurations les plus courants. D&apos;autres variantes de véhicules peuvent être configurées dans l&apos;onglet &quot;Véhicule&quot; &gt; &quot;Personnalisé&quot; du plugin de configuration de GCS.
Veuillez sélectionner le type de véhicule terrestre dont vous voulez créer la configuration ci-dessous :</translation>
</message>
<message>
<location line="+6"/>
<source>Car</source>
<translation>Voiture</translation>
</message>
<message>
<location line="+1"/>
<source>This setup expects a traditional car with a rear motor and a front streering servo</source>
<translation>Cette configuration correspond à une voiture classique avec un moteur à l&apos;arrière et un servo de direction à l&apos;avant</translation>
</message>
<message>
<location line="+4"/>
<source>Tank</source>
<translation>Tank</translation>
</message>
<message>
<location line="+1"/>
<source>This setup expects a traditional vehicle using only two motors and differential steering</source>
<translation>Cette configuration correspond à une véhicule classique utilisant deux moteurs et une direction par différentiel entre ces moteurs</translation>
</message>
<message>
<location line="+4"/>
<source>Motorcycle</source>
<translation>Motocycle</translation>
</message>
<message>
<location line="+1"/>
<source>This setup currently expects a motorcyle setup, using one motor and one servo for steering.</source>
<translation type="unfinished">Cette configuration correspond à une moto utilisant un moteur et un servo pour la direction.</translation>
</message>
</context>
<context>
<name>VehiclePage</name>
@ -9898,8 +9979,7 @@ persistant de la carte, et ensuite ferme la boite de dialogue.</translation>
<message>
<location line="+28"/>
<source>http://wiki.openpilot.org/display/Doc/UAV+Settings+import-export</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/IQCJAQ</translation>
<translation></translation>
</message>
</context>
<context>
@ -10417,8 +10497,7 @@ p, li { white-space: pre-wrap; }
<message>
<location line="+15"/>
<source>http://wiki.openpilot.org/x/D4AUAQ</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/HoBqAQ</translation>
<translation></translation>
</message>
</context>
<context>
@ -10431,8 +10510,7 @@ p, li { white-space: pre-wrap; }
<message>
<location line="+58"/>
<source>http://wiki.openpilot.org/x/44Cf</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/IIBqAQ</translation>
<translation></translation>
</message>
</context>
<context>
@ -10453,26 +10531,24 @@ Voulez-vous toujours continuer ?</translation>
<context>
<name>ConfigInputWidget</name>
<message>
<location filename="../../../src/plugins/config/configinputwidget.cpp" line="+380"/>
<location filename="../../../src/plugins/config/configinputwidget.cpp" line="+385"/>
<source>http://wiki.openpilot.org/x/04Cf</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/aIBqAQ</translation>
<translation></translation>
</message>
<message>
<location line="+7"/>
<location line="+1176"/>
<source>Arming Settings are now set to &apos;Always Disarmed&apos; for your safety.</source>
<translatorcomment>Contexte : Onglet &quot;Paramètres d&apos;Armement&quot;</translatorcomment>
<translation>Pour des raisons de sécurité les Paramètres d&apos;Armement ont é modifiés à &apos;Toujours Désarmé&apos;.</translation>
</message>
<message>
<location line="-1175"/>
<location line="+1"/>
<source>You will have to reconfigure the arming settings manually when the wizard is finished. After the last step of the wizard you will be taken to the Arming Settings screen.</source>
<translatorcomment>redirigé vers / sur ?</translatorcomment>
<translation>Vous devrez reconfigurer manuellement les paramètres d&apos;armement lorsque l&apos;assistant sera terminé. Après la dernière étape de l&apos;assistant, vous serez redirigé vers l&apos;écran des Paramètres d&apos;Armement.</translation>
</message>
<message>
<location line="+213"/>
<location line="+224"/>
<source>Next</source>
<translation>Suivant</translation>
</message>
@ -10668,9 +10744,28 @@ Bougez le manche %1.</translation>
<translation> Vous avez la possibilité d&apos;appuyer sur Suivant pour ignorer ce canal.</translation>
</message>
<message>
<location line="+690"/>
<location line="+725"/>
<source>Stop Manual Calibration</source>
<translation>Arrêter Calibration Manuelle</translation>
</message>
<message>
<location line="+3"/>
<source>&lt;p&gt;Arming Settings are now set to &apos;Always Disarmed&apos; for your safety.&lt;/p&gt;&lt;p&gt;Be sure your receiver is powered with an external source and Transmitter is on.&lt;/p&gt;&lt;p align=&apos;center&apos;&gt;&lt;b&gt;Stop Manual Calibration&lt;/b&gt; when done&lt;/p&gt;</source>
<translation>&lt;p&gt;Pour des raisons de sécurité les Paramètres d&apos;Armement ont é modifiés à &apos;Toujours Désarmé&apos;.&lt;/p&gt;&lt;p&gt;Veuillez vérifier que votre récepteur est alimenté avec une source externe et que la radio Rx est allumée. &lt;p align=&apos;center&apos;&gt;&lt;b&gt;Arrêter Calibration Manuelle&lt;/b&gt; à la fin&lt;/p&gt;</translation>
</message>
<message>
<location line="+3"/>
<source>You will have to reconfigure the arming settings manually when the manual calibration is finished.</source>
<translation>Vous devrez reconfigurer les paramètres d&apos;armement manuellement lorsque la calibration manuelle sera terminée.</translation>
</message>
<message>
<location line="+33"/>
<source>Start Manual Calibration</source>
<translation>Démarrer Calibration Manuelle</translation>
</message>
<message>
<source>You will have to reconfigure the arming settings manually when the wizard is finished.</source>
<translation>Vous devrez reconfigurer les paramètres d&apos;armement manuellement lorsque l&apos;assistant sera terminé.</translation>
<translation type="vanished">Vous devrez reconfigurer les paramètres d&apos;armement manuellement lorsque l&apos;assistant sera terminé.</translation>
</message>
</context>
<context>
@ -10950,12 +11045,27 @@ Bougez le manche %1.</translation>
<context>
<name>ScopeGadgetWidget</name>
<message>
<location filename="../../../src/plugins/scope/scopegadgetwidget.cpp" line="+219"/>
<location filename="../../../src/plugins/scope/scopegadgetwidget.cpp" line="+232"/>
<source>Click legend to show/hide scope trace.
Double click legend or plot to show/hide legend.</source>
<translation>Cliquer sur la légende pour afficher/cacher le tracé du graphique.
Double clic sur la légende ou le tracé pour afficher/cacher la légende.</translation>
</message>
<message>
<location line="+410"/>
<source>Clear</source>
<translation>Effacer</translation>
</message>
<message>
<location line="+2"/>
<source>Copy to Clipboard</source>
<translation>Copier dans le Presse-papiers</translation>
</message>
<message>
<location line="+3"/>
<source>Options...</source>
<translation>Options...</translation>
</message>
</context>
<context>
<name>SetupWizard</name>
@ -10965,7 +11075,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<translation>Assistant Configuration OpenPilot</translation>
</message>
<message>
<location line="+172"/>
<location line="+177"/>
<source>Controller type: </source>
<translation>Type de contrôleur : </translation>
</message>
@ -11001,18 +11111,19 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
</message>
<message>
<location line="+3"/>
<location line="+50"/>
<location line="+47"/>
<location line="+21"/>
<location line="+12"/>
<location line="+24"/>
<location line="+6"/>
<location line="+19"/>
<location line="+13"/>
<location line="+15"/>
<location line="+16"/>
<location line="+38"/>
<source>Unknown</source>
<translation>Inconnu</translation>
</message>
<message>
<location line="-163"/>
<location line="-179"/>
<source>Vehicle type: </source>
<translation>Type de véhicule : </translation>
</message>
@ -11023,12 +11134,13 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
</message>
<message>
<location line="+3"/>
<location line="+48"/>
<location line="+45"/>
<location line="+24"/>
<source>Vehicle sub type: </source>
<translation>Sous-type véhicule : </translation>
</message>
<message>
<location line="-45"/>
<location line="-66"/>
<source>Tricopter</source>
<translation>Tricoptère</translation>
</message>
@ -11043,9 +11155,8 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<translation>Quadricoptère +</translation>
</message>
<message>
<location line="+3"/>
<source>Quadcopter H</source>
<translation>Quadricoptère H</translation>
<translation type="vanished">Quadricoptère H</translation>
</message>
<message>
<location line="+3"/>
@ -11118,7 +11229,22 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<translation>Véhicule surface</translation>
</message>
<message>
<location line="+7"/>
<location line="+6"/>
<source>Car</source>
<translation>Voiture</translation>
</message>
<message>
<location line="+3"/>
<source>Tank</source>
<translation>Tank</translation>
</message>
<message>
<location line="+3"/>
<source>Motorcycle</source>
<translation>Motocycle</translation>
</message>
<message>
<location line="+13"/>
<source>Input type: </source>
<translation>Type d&apos;entrée : </translation>
</message>
@ -11140,7 +11266,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<message>
<location line="+3"/>
<source>Spektrum Satellite</source>
<translation type="unfinished"></translation>
<translation></translation>
</message>
<message>
<location line="+7"/>
@ -11158,7 +11284,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<translation>Contrôleur Rapide (%1 Hz)</translation>
</message>
<message>
<location line="+9"/>
<location line="+10"/>
<source>Servo type: </source>
<translation>Type Servo : </translation>
</message>
@ -11258,7 +11384,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<message>
<location line="+32"/>
<source>Writing Airspeed sensor settings</source>
<translation type="unfinished">Écriture paramètres capteur Vitesse Air</translation>
<translation>Écriture paramètres capteur Vitesse Air</translation>
</message>
<message>
<location line="+7"/>
@ -11266,13 +11392,14 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<translation>Écriture paramètres matériels</translation>
</message>
<message>
<location line="+155"/>
<location line="+172"/>
<location line="+31"/>
<location line="+36"/>
<source>Writing actuator settings</source>
<translation>Écriture paramètres actionneurs</translation>
</message>
<message>
<location line="+60"/>
<location line="+52"/>
<source>Writing flight mode settings 1/2</source>
<translation>Écriture paramètres mode de vol 1/2</translation>
</message>
@ -11298,7 +11425,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<translation>Écriture paramètres de stabilisation</translation>
</message>
<message>
<location line="+106"/>
<location line="+135"/>
<source>Writing mixer settings</source>
<translation>Écriture paramètres mixeur</translation>
</message>
@ -11534,8 +11661,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<message>
<location line="-308"/>
<source>http://wiki.openpilot.org/display/Doc/Erase+board+settings</source>
<translatorcomment>Wiki FR - Uploader</translatorcomment>
<translation>http://wiki.openpilot.org/x/SYBqAQ</translation>
<translation></translation>
</message>
<message>
<location line="+46"/>
@ -11639,8 +11765,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.</tran
<message>
<location line="+38"/>
<source>http://wiki.openpilot.org/x/AoBZ</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/SYBqAQ</translation>
<translation></translation>
</message>
<message>
<location line="+7"/>
@ -12256,39 +12381,32 @@ La carte sera redémarrée et tous les paramètres effacés.</translation>
<translation>Affectations sorties</translation>
</message>
<message>
<location/>
<source>Engine</source>
<translation>Moteur</translation>
<translation type="vanished">Moteur</translation>
</message>
<message>
<location/>
<source>Select output channel for the engine</source>
<translation>Sélectionner le canal de sortie pour le moteur</translation>
<translation type="vanished">Sélectionner le canal de sortie pour le moteur</translation>
</message>
<message>
<location/>
<source>Aileron 1</source>
<translation>Aileron 1</translation>
<translation type="vanished">Aileron 1</translation>
</message>
<message>
<location/>
<source>Select output channel for the first aileron (or elevon)</source>
<translation>Sélectionner le canal de sortie pour le premier aileron (ou élevon)</translation>
<translation type="vanished">Sélectionner le canal de sortie pour le premier aileron (ou élevon)</translation>
</message>
<message>
<location/>
<source>Aileron 2</source>
<translation>Aileron 2</translation>
<translation type="vanished">Aileron 2</translation>
</message>
<message>
<location/>
<source>Select output channel for the second aileron (or elevon)</source>
<translation>Sélectionner le canal de sortie pour le second aileron (ou élevon)</translation>
<translation type="vanished">Sélectionner le canal de sortie pour le second aileron (ou élevon)</translation>
</message>
<message>
<location/>
<source>Motor</source>
<translation>Moteur</translation>
<translation type="vanished">Moteur</translation>
</message>
<message>
<location/>
@ -12360,6 +12478,16 @@ La carte sera redémarrée et tous les paramètres effacés.</translation>
<source>Mixer OK</source>
<translation></translation>
</message>
<message>
<location/>
<source>Motor 1</source>
<translation>Moteur 1</translation>
</message>
<message>
<location/>
<source>Vehicle frame</source>
<translation></translation>
</message>
</context>
<context>
<name>MultiRotorConfigWidget</name>
@ -12943,8 +13071,7 @@ Méfiez-vous de ne pas vous verrouiller l&apos;accès !</translation>
<message>
<location/>
<source>url:http://wiki.openpilot.org/x/hgAGAQ</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>url:http://wiki.openpilot.org/x/B4BYAQ</translation>
<translation></translation>
</message>
</context>
<context>
@ -13130,8 +13257,7 @@ p, li { white-space: pre-wrap; }
<message>
<location line="+253"/>
<source>http://wiki.openpilot.org/x/WIGf</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/aoBqAQ</translation>
<translation></translation>
</message>
</context>
<context>
@ -13144,8 +13270,7 @@ p, li { white-space: pre-wrap; }
<message>
<location line="+226"/>
<source>http://wiki.openpilot.org/x/GgDBAQ</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/TYRNAQ</translation>
<translation></translation>
</message>
</context>
<context>
@ -14267,7 +14392,7 @@ Des valeurs trop élevées pour les contrôles principaux peuvent entraîner des
et même conduire au crash. A utiliser avec prudence.</translation>
</message>
<message>
<location filename="../../../src/plugins/config/inputchannelform.cpp" line="+138"/>
<location filename="../../../src/plugins/config/inputchannelform.cpp" line="+172"/>
<source>Chan %1</source>
<translation>Canal %1</translation>
</message>
@ -14276,6 +14401,16 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<source>Text</source>
<translation type="unfinished">Texte</translation>
</message>
<message>
<location/>
<source>Channel value</source>
<translation>Valeur canal</translation>
</message>
<message>
<location/>
<source>Channel Value</source>
<translation>Valeur Canal</translation>
</message>
</context>
<context>
<name>ConfigVehicleTypeWidget</name>
@ -14307,8 +14442,7 @@ et même conduire au crash. A utiliser avec prudence.</translation>
<message>
<location line="+315"/>
<source>http://wiki.openpilot.org/x/44Cf</source>
<translatorcomment>Lien Wiki FR</translatorcomment>
<translation>http://wiki.openpilot.org/x/IIBqAQ</translation>
<translation></translation>
</message>
</context>
<context>
@ -14677,7 +14811,7 @@ It is suggested that if this is a first time configuration of your controller, r
Il est suggéré que si cela est une première configuration de votre contrôleur, plutôt que d&apos;utiliser cette option, sélectionnez à la place un ensemble de réglages qui correspond le mieux à votre propre appareil dans la liste ci-dessus. Si vous n&apos;êtes pas en mesure d&apos;en choisir un, sélectionnez l&apos;élément générique de la liste.</translation>
</message>
<message>
<location line="+77"/>
<location line="+85"/>
<source>Current Tuning</source>
<translation>Réglages Actuels</translation>
</message>
@ -15011,9 +15145,8 @@ p, li { white-space: pre-wrap; }
<translation>Multirotor - Quadricoptère X</translation>
</message>
<message>
<location line="+5"/>
<source>Multirotor - Quadrocopter H</source>
<translation>Multirotor - Quadricoptère H</translation>
<translation type="vanished">Multirotor - Quadricoptère H</translation>
</message>
<message>
<location line="+5"/>

View File

@ -19,8 +19,6 @@ include( $${QWT_ROOT}/qwtconfig.pri )
# include( $${QWT_ROOT}/qwtbuild.pri )
# include( $${QWT_ROOT}/qwtfunctions.pri )
include(../../../openpilotgcslibrary.pri)
# QWT_OUT_ROOT = $${OUT_PWD}/..
TEMPLATE = lib
@ -31,6 +29,12 @@ DEFINES += QWT_LIBRARY
# DESTDIR = $${QWT_OUT_ROOT}/lib
# NOTE: The include below must come AFTER the TARGET is
# defined. Otherwise the debug version of the library
# will not have the 'd' suffix it needs.
#
include(../../../openpilotgcslibrary.pri)
contains(QWT_CONFIG, QwtDll) {
CONFIG += dll

View File

@ -12,7 +12,7 @@ contains(QT_CONFIG, reduce_exports):CONFIG += hGCS_symbols
macx {
QMAKE_LFLAGS_SONAME = -Wl,-install_name,@executable_path/../Plugins/
} else
} else {
win32 {
target.path = /bin
target.files = $$DESTDIR/$${TARGET}.dll

View File

@ -148,6 +148,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
}
addWidgetBinding("ManualControlSettings", "Deadband", ui->deadband, 0, 0.01f);
addWidgetBinding("ManualControlSettings", "DeadbandAssistedControl", ui->assistedControlDeadband, 0, 0.01f);
connect(ui->configurationWizard, SIGNAL(clicked()), this, SLOT(goToWizard()));
connect(ui->stackedWidget, SIGNAL(currentChanged(int)), this, SLOT(disableWizardButton(int)));
@ -1494,26 +1495,32 @@ void ConfigInputWidget::updatePositionSlider()
case 6:
ui->fmsModePos6->setEnabled(true);
ui->pidBankSs1_5->setEnabled(true);
ui->assistControlPos6->setEnabled(true);
// pass through
case 5:
ui->fmsModePos5->setEnabled(true);
ui->pidBankSs1_4->setEnabled(true);
ui->assistControlPos5->setEnabled(true);
// pass through
case 4:
ui->fmsModePos4->setEnabled(true);
ui->pidBankSs1_3->setEnabled(true);
ui->assistControlPos4->setEnabled(true);
// pass through
case 3:
ui->fmsModePos3->setEnabled(true);
ui->pidBankSs1_2->setEnabled(true);
ui->assistControlPos3->setEnabled(true);
// pass through
case 2:
ui->fmsModePos2->setEnabled(true);
ui->pidBankSs1_1->setEnabled(true);
ui->assistControlPos2->setEnabled(true);
// pass through
case 1:
ui->fmsModePos1->setEnabled(true);
ui->pidBankSs1_0->setEnabled(true);
ui->assistControlPos1->setEnabled(true);
// pass through
case 0:
break;
@ -1523,26 +1530,32 @@ void ConfigInputWidget::updatePositionSlider()
case 0:
ui->fmsModePos1->setEnabled(false);
ui->pidBankSs1_0->setEnabled(false);
ui->assistControlPos1->setEnabled(false);
// pass through
case 1:
ui->fmsModePos2->setEnabled(false);
ui->pidBankSs1_1->setEnabled(false);
ui->assistControlPos2->setEnabled(false);
// pass through
case 2:
ui->fmsModePos3->setEnabled(false);
ui->pidBankSs1_2->setEnabled(false);
ui->assistControlPos3->setEnabled(false);
// pass through
case 3:
ui->fmsModePos4->setEnabled(false);
ui->pidBankSs1_3->setEnabled(false);
ui->assistControlPos4->setEnabled(false);
// pass through
case 4:
ui->fmsModePos5->setEnabled(false);
ui->pidBankSs1_4->setEnabled(false);
ui->assistControlPos5->setEnabled(false);
// pass through
case 5:
ui->fmsModePos6->setEnabled(false);
ui->pidBankSs1_5->setEnabled(false);
ui->assistControlPos6->setEnabled(false);
// pass through
case 6:
default:
@ -1702,7 +1715,7 @@ void ConfigInputWidget::resetActuatorSettings()
// 1500 = servo middle, can be applied to all outputs because board is 'Alwaysdisarmed'
for (unsigned int output = 0; output < 12; output++) {
actuatorSettingsData.ChannelMax[output] = 1500;
actuatorSettingsData.ChannelMin[output] = 1500;
actuatorSettingsData.ChannelMin[output] = 1000;
actuatorSettingsData.ChannelNeutral[output] = 1500;
actuatorSettingsObj->setData(actuatorSettingsData);
}

View File

@ -32,6 +32,12 @@
#include <oplinkstatus.h>
#include <QMessageBox>
// Channel range and Frequency display
static const int MAX_CHANNEL_NUM = 250;
static const int MIN_CHANNEL_RANGE = 10;
static const float FIRST_FREQUENCY = 430.000;
static const float FREQUENCY_STEP = 0.040;
ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_oplink = new Ui_OPLinkWidget();
@ -97,6 +103,14 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
// Connect the selection changed signals.
connect(m_oplink->PPMOnly, SIGNAL(toggled(bool)), this, SLOT(ppmOnlyChanged()));
connect(m_oplink->MinimumChannel, SIGNAL(valueChanged(int)), this, SLOT(minChannelChanged()));
connect(m_oplink->MaximumChannel, SIGNAL(valueChanged(int)), this, SLOT(maxChannelChanged()));
m_oplink->MinimumChannel->setKeyboardTracking(false);
m_oplink->MaximumChannel->setKeyboardTracking(false);
m_oplink->MaximumChannel->setMaximum(MAX_CHANNEL_NUM);
m_oplink->MinimumChannel->setMaximum(MAX_CHANNEL_NUM - MIN_CHANNEL_RANGE);
// Request and update of the setting object.
settingsUpdated = false;
@ -318,6 +332,50 @@ void ConfigPipXtremeWidget::ppmOnlyChanged()
m_oplink->ComSpeed->setEnabled(!is_ppm_only);
}
void ConfigPipXtremeWidget::minChannelChanged()
{
channelChanged(false);
}
void ConfigPipXtremeWidget::maxChannelChanged()
{
channelChanged(true);
}
void ConfigPipXtremeWidget::channelChanged(bool isMax)
{
int minChannel = m_oplink->MinimumChannel->value();
int maxChannel = m_oplink->MaximumChannel->value();
if ((maxChannel - minChannel) < MIN_CHANNEL_RANGE) {
if (isMax) {
minChannel = maxChannel - MIN_CHANNEL_RANGE;
} else {
maxChannel = minChannel + MIN_CHANNEL_RANGE;
}
if (maxChannel > MAX_CHANNEL_NUM) {
maxChannel = MAX_CHANNEL_NUM;
minChannel = MAX_CHANNEL_NUM - MIN_CHANNEL_RANGE;
}
if (minChannel < 0) {
minChannel = 0;
maxChannel = MIN_CHANNEL_RANGE;
}
}
m_oplink->MaximumChannel->setValue(maxChannel);
m_oplink->MinimumChannel->setValue(minChannel);
// Calculate and Display frequency in MHz
float minFrequency = FIRST_FREQUENCY + (minChannel * FREQUENCY_STEP);
float maxFrequency = FIRST_FREQUENCY + (maxChannel * FREQUENCY_STEP);
m_oplink->MinFreq->setText("(" + QString::number(minFrequency, 'f', 3) + " MHz)");
m_oplink->MaxFreq->setText("(" + QString::number(maxFrequency, 'f', 3) + " MHz)");
}
/**
@}
@}

View File

@ -62,6 +62,9 @@ private slots:
void disconnected();
void bind();
void ppmOnlyChanged();
void minChannelChanged();
void maxChannelChanged();
void channelChanged(bool isMax);
};
#endif // CONFIGTXPIDWIDGET_H

View File

@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>796</width>
<height>591</height>
<width>1250</width>
<height>755</height>
</rect>
</property>
<property name="windowTitle">
@ -234,6 +234,29 @@
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="labelAssistedControlDeadband">
<property name="text">
<string>Assisted Control stick deadband </string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QDoubleSpinBox" name="assistedControlDeadband">
<property name="toolTip">
<string>Assisted Control stick deadband in percents of full range (2-12) for use with GPSAssist. This can not be disabled.</string>
</property>
<property name="decimals">
<number>1</number>
</property>
<property name="minimum">
<double>2.000000000000000</double>
</property>
<property name="maximum">
<double>12.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
<item>
@ -1206,197 +1229,6 @@ font:bold;</string>
<property name="horizontalSpacing">
<number>6</number>
</property>
<item row="0" column="6">
<widget class="QLabel" name="label_111">
<property name="minimumSize">
<size>
<width>80</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Settings Bank</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="10">
<widget class="QLabel" name="label_16">
<property name="minimumSize">
<size>
<width>138</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Flight Mode Count</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="10">
<widget class="QSpinBox" name="fmsPosNum">
<property name="toolTip">
<string>Number of positions your FlightMode switch has.
Default is 3.
It will be 2 or 3 for most of setups, but it also can be up to 6.
In that case you have to configure your radio mixers so the whole range
from min to max is split into N equal intervals, and you may set arbitrary
channel value for each flight mode.</string>
</property>
<property name="minimum">
<number>1</number>
</property>
<property name="maximum">
<number>6</number>
</property>
<property name="value">
<number>3</number>
</property>
</widget>
</item>
<item row="2" column="10">
<widget class="QLabel" name="label_15">
<property name="sizePolicy">
<sizepolicy hsizetype="Ignored" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Avoid &amp;quot;Manual&amp;quot; for multirotors! Never select &amp;quot;Altitude&amp;quot;, &amp;quot;VelocityControl&amp;quot; or &amp;quot;CruiseControl&amp;quot; on a fixed wing!&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="3">
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="7">
<spacer name="horizontalSpacer_16">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="1">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="8" rowspan="3">
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_13">
<property name="minimumSize">
<size>
<width>138</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Flight Mode</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="0" rowspan="2">
<widget class="QFrame" name="frame">
<property name="minimumSize">
@ -1941,6 +1773,418 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
</layout>
</widget>
</item>
<item row="0" column="6">
<widget class="QLabel" name="label_111">
<property name="minimumSize">
<size>
<width>138</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Settings Bank</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="12">
<widget class="QLabel" name="label_16">
<property name="minimumSize">
<size>
<width>138</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Flight Mode Count</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="12">
<widget class="QSpinBox" name="fmsPosNum">
<property name="toolTip">
<string>Number of positions your FlightMode switch has.
Default is 3.
It will be 2 or 3 for most of setups, but it also can be up to 6.
In that case you have to configure your radio mixers so the whole range
from min to max is split into N equal intervals, and you may set arbitrary
channel value for each flight mode.</string>
</property>
<property name="minimum">
<number>1</number>
</property>
<property name="maximum">
<number>6</number>
</property>
<property name="value">
<number>3</number>
</property>
</widget>
</item>
<item row="2" column="12">
<widget class="QLabel" name="label_15">
<property name="sizePolicy">
<sizepolicy hsizetype="Ignored" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Avoid &amp;quot;Manual&amp;quot; for multirotors! Never select &amp;quot;Altitude&amp;quot;, &amp;quot;VelocityControl&amp;quot; or &amp;quot;CruiseControl&amp;quot; on a fixed wing!&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="3">
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="7">
<spacer name="horizontalSpacer_16">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="1">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="10" rowspan="3">
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_13">
<property name="minimumSize">
<size>
<width>138</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Flight Mode</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="8">
<widget class="QLabel" name="label_20">
<property name="minimumSize">
<size>
<width>138</width>
<height>0</height>
</size>
</property>
<property name="layoutDirection">
<enum>Qt::LeftToRight</enum>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:1px;
font:bold;</string>
</property>
<property name="text">
<string>Assisted Control</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="8" rowspan="2">
<widget class="QFrame" name="frame_4">
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_4">
<property name="leftMargin">
<number>1</number>
</property>
<property name="topMargin">
<number>1</number>
</property>
<property name="rightMargin">
<number>1</number>
</property>
<property name="bottomMargin">
<number>1</number>
</property>
<item>
<widget class="QComboBox" name="assistControlPos1">
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeAssistMap</string>
<string>index:0</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="assistControlPos2">
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeAssistMap</string>
<string>index:1</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="assistControlPos3">
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeAssistMap</string>
<string>index:2</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="assistControlPos4">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeAssistMap</string>
<string>index:3</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="assistControlPos5">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeAssistMap</string>
<string>index:4</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="assistControlPos6">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeAssistMap</string>
<string>index:5</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
</item>

View File

@ -6,7 +6,7 @@
<rect>
<x>0</x>
<y>0</y>
<width>834</width>
<width>971</width>
<height>652</height>
</rect>
</property>
@ -49,8 +49,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>810</width>
<height>575</height>
<width>949</width>
<height>558</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout_5">
@ -72,14 +72,14 @@
<string>Configuration</string>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<item row="4" column="3">
<item row="4" column="4">
<widget class="QComboBox" name="ComSpeed">
<property name="statusTip">
<string>Com speed in bps.</string>
</property>
</widget>
</item>
<item row="4" column="2">
<item row="4" column="3">
<widget class="QLabel" name="ComSpeedLabel">
<property name="font">
<font>
@ -95,7 +95,7 @@
</property>
</widget>
</item>
<item row="9" column="2">
<item row="9" column="3">
<widget class="QLabel" name="VCPPortLabel">
<property name="font">
<font>
@ -111,7 +111,7 @@
</property>
</widget>
</item>
<item row="7" column="3">
<item row="7" column="4">
<widget class="QComboBox" name="FlexiPort">
<property name="maximumSize">
<size>
@ -124,7 +124,7 @@
</property>
</widget>
</item>
<item row="6" column="2">
<item row="6" column="3">
<widget class="QLabel" name="MainPortLabel">
<property name="font">
<font>
@ -140,7 +140,7 @@
</property>
</widget>
</item>
<item row="6" column="3">
<item row="6" column="4">
<widget class="QComboBox" name="MainPort">
<property name="maximumSize">
<size>
@ -153,7 +153,20 @@
</property>
</widget>
</item>
<item row="0" column="3">
<item row="9" column="4">
<widget class="QComboBox" name="VCPPort">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the USB virtual com port</string>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QComboBox" name="MaxRFTxPower">
<property name="maximumSize">
<size>
@ -172,7 +185,7 @@
</property>
</widget>
</item>
<item row="0" column="2">
<item row="0" column="3">
<widget class="QLabel" name="MaxRFTxPowerLabel">
<property name="font">
<font>
@ -188,20 +201,10 @@
</property>
</widget>
</item>
<item row="9" column="3">
<widget class="QComboBox" name="VCPPort">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Choose the function for the USB virtual com port</string>
</property>
</widget>
<item row="10" column="4">
<widget class="QComboBox" name="FlexiIOPort"/>
</item>
<item row="10" column="2">
<item row="10" column="3">
<widget class="QLabel" name="FlexiIOPortLabel">
<property name="font">
<font>
@ -217,10 +220,29 @@
</property>
</widget>
</item>
<item row="10" column="3">
<widget class="QComboBox" name="FlexiIOPort"/>
<item row="6" column="1">
<widget class="QSpinBox" name="MaximumChannel">
<property name="maximumSize">
<size>
<width>60</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="toolTip">
<string>Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz.</string>
</property>
<property name="maximum">
<number>250</number>
</property>
</widget>
</item>
<item row="7" column="2">
<item row="7" column="3">
<widget class="QLabel" name="FlexiPortLabel">
<property name="font">
<font>
@ -252,22 +274,6 @@
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QSpinBox" name="MaximumChannel">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="toolTip">
<string>Channel 0 is 430 MHz, channel 249 is 440 MHz, and the channel spacing is 40 KHz.</string>
</property>
<property name="maximum">
<number>249</number>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="MinimumChannelLabel">
<property name="font">
@ -286,6 +292,12 @@
</item>
<item row="7" column="1">
<widget class="QSpinBox" name="MinimumChannel">
<property name="maximumSize">
<size>
<width>60</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>50</weight>
@ -293,10 +305,10 @@
</font>
</property>
<property name="toolTip">
<string>Channel 0 is 430 MHz, channel 249 is 440 MHz, and the channel spacing is 40 KHz.</string>
<string>Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz.</string>
</property>
<property name="maximum">
<number>249</number>
<number>250</number>
</property>
</widget>
</item>
@ -318,6 +330,12 @@
</item>
<item row="9" column="1">
<widget class="QSpinBox" name="ChannelSet">
<property name="maximumSize">
<size>
<width>60</width>
<height>16777215</height>
</size>
</property>
<property name="font">
<font>
<weight>50</weight>
@ -328,7 +346,68 @@
<string>Sets the random sequence of channels to use for frequency hopping.</string>
</property>
<property name="maximum">
<number>249</number>
<number>250</number>
</property>
</widget>
</item>
<item row="10" column="0" colspan="2">
<widget class="QCheckBox" name="Coordinator">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="statusTip">
<string>This modem will be a coordinator and other modems will bind to it.</string>
</property>
<property name="text">
<string>Coordinator</string>
</property>
</widget>
</item>
<item row="6" column="2">
<widget class="QLabel" name="MaxFreq">
<property name="maximumSize">
<size>
<width>110</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>440.000 (MHz)</string>
</property>
</widget>
</item>
<item row="7" column="2">
<widget class="QLabel" name="MinFreq">
<property name="maximumSize">
<size>
<width>110</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>430.000 (MHz)</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QCheckBox" name="OneWayLink">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="acceptDrops">
<bool>false</bool>
</property>
<property name="statusTip">
<string>If selected, data will only be transmitted from the coordinator to the Rx modem.</string>
</property>
<property name="text">
<string>One-Way</string>
</property>
</widget>
</item>
@ -349,22 +428,6 @@
</widget>
</item>
<item row="0" column="1">
<widget class="QCheckBox" name="OneWayLink">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="statusTip">
<string>If selected, data will only be transmitted from the coordinator to the Rx modem.</string>
</property>
<property name="text">
<string>One-Way</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QCheckBox" name="PPM">
<property name="font">
<font>
@ -380,22 +443,6 @@
</property>
</widget>
</item>
<item row="10" column="0" colspan="2">
<widget class="QCheckBox" name="Coordinator">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="statusTip">
<string>This modem will be a coordinator and other modems will bind to it.</string>
</property>
<property name="text">
<string>Coordinator</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>

View File

@ -0,0 +1,5 @@
<RCC>
<qresource prefix="/pfdqml">
<file>fonts/PTS75F.ttf</file>
</qresource>
</RCC>

View File

@ -0,0 +1,26 @@
Copyright © 2009 ParaType Ltd.
with Reserved Names &amp;quot;PT Sans&amp;quot; and &amp;quot;ParaType&amp;quot;.
FONT LICENSE
PERMISSION &amp;amp; CONDITIONS
Permission is hereby granted, free of charge, to any person obtaining a copy of the font software, to use, study, copy, merge, embed, modify, redistribute, and sell modified and unmodified copies of the font software, subject to the following conditions:
1) Neither the font software nor any of its individual components, in original or modified versions, may be sold by itself.
2) Original or modified versions of the font software may be bundled, redistributed and/or sold with any software, provided that each copy contains the above copyright notice and this license. These can be included either as stand-alone text files, human-readable headers or in the appropriate machine-readable metadata fields within text or binary files as long as those fields can be easily viewed by the user.
3) No modified version of the font software may use the Reserved Name(s) or combinations of Reserved Names with other words unless explicit written permission is granted by the ParaType. This restriction only applies to the primary font name as presented to the users.
4) The name of ParaType or the author(s) of the font software shall not be used to promote, endorse or advertise any modified version, except to acknowledge the contribution(s) of ParaType and the author(s) or with explicit written permission of ParaType.
5) The font software, modified or unmodified, in part or in whole, must be distributed entirely under this license, and must not be distributed under any other license. The requirement for fonts to remain under this license does not apply to any document created using the Font Software.
TERMINATION &amp;amp; TERRITORY
This license has no limits on time and territory, but it becomes null and void if any of the above conditions are not met.
DISCLAIMER
THE FONT SOFTWARE IS PROVIDED &amp;quot;AS IS&amp;quot;, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO ANY WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT OF COPYRIGHT, PATENT, TRADEMARK, OR OTHER RIGHT. IN NO EVENT SHALL PARATYPE BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, INCLUDING ANY GENERAL, SPECIAL, INDIRECT, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF THE USE OR INABILITY TO USE THE FONT SOFTWARE OR FROM OTHER DEALINGS IN THE FONT SOFTWARE.
ParaType Ltd
http://www.paratype.ru

View File

@ -40,3 +40,6 @@ OTHER_FILES += PfdQml.pluginspec
FORMS += pfdqmlgadgetoptionspage.ui
RESOURCES += \
PfdResources.qrc

View File

@ -141,7 +141,7 @@ void ConnectionDiagram::setupGraphicsScene()
break;
default:
break;
}
}
case VehicleConfigurationSource::VEHICLE_SURFACE:
switch (m_configSource->getVehicleSubType()) {
case VehicleConfigurationSource::GROUNDVEHICLE_CAR:
@ -156,7 +156,7 @@ void ConnectionDiagram::setupGraphicsScene()
default:
break;
}
case VehicleConfigurationSource::VEHICLE_HELI:
case VehicleConfigurationSource::VEHICLE_HELI:
default:
break;
}

View File

@ -5,9 +5,13 @@
<style></style>
</head>
<body>
<h1>Attitude: Critical</h1>
<h1>Attitude : Critical</h1>
<p>
This alarm will remain set until data is received from the accelerometer.
One of the following conditions may be present:
<ul>
<li>No data is received from the accelerometer</li>
<li>Waiting for good data from Magnetometer or GPS lock to perform module initialization.</li>
</ul>
</p>
</body>
</html>
</html>

View File

@ -5,9 +5,13 @@
<style></style>
</head>
<body>
<h1>Attitude: Error</h1>
<h1>Attitude : Error</h1>
<p>
Failed to get an update from the accelerometer or gyros.
One of the following conditions may be present:
<ul>
<li>Failed to get an update from the accelerometer or gyros.</li>
<li>Attitude Estimation Algorithm set to "GPS Navigation (INS13)" and no Magnetometer : please set HomeLocation.</li>
</ul>
</p>
</body>
</html>
</html>

View File

@ -0,0 +1,18 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Magnetometer : Critical</h1>
<p>
Data is coming from the magnetometer, but the readings are off by over 15%. This can be caused by various reasons:
</p>
<ul>
<li>Magnetometer has not been calibrated.</li>
<li>Something is interfering with the magnetometer. (High current)</li>
</ul>
</p>
</body>
</html>

View File

@ -5,9 +5,9 @@
<style></style>
</head>
<body>
<h1>Stack: Critical</h1>
<h1>Magnetometer : Warning</h1>
<p>
Stack overflow
Magnetometer readings are off by over 5%
</p>
</body>
</html>
</html>

View File

@ -7,7 +7,11 @@
<body>
<h1>Memory: Critical</h1>
<p>
Either the remaining heap space or the IRQ stack has fallen below the <b>critical</b> limit (1000 bytes heap, 80 entries IRQ stack).
Either the remaining heap space or the IRQ stack has fallen below the <b>critical</b> limit.
</p>
<ul>
<li>Revo : 500 bytes heap, 80 entries IRQ stack.</li>
<li>CC/CC3D : 40 bytes heap, 60 entries IRQ stack.</li>
<ul>
</body>
</html>
</html>

View File

@ -9,8 +9,12 @@
<p>
Either the remaining heap space or the IRQ stack has fallen below the <b>warning</b> limit (4000 bytes heap, 150 entries IRQ stack).
</p>
<ul>
<li>Revo : 1000 bytes heap, 150 entries IRQ stack.</li>
<li>CC/CC3D : 220 bytes heap, 100 entries IRQ stack.</li>
<ul>
<p>
<b>Note:</b> if this is an original CC board (not CC3D or Revo), this condition is normal.
</p>
</body>
</html>
</html>

View File

@ -0,0 +1,13 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Pathplanner : Warning</h1>
<p>
No path plan has been uploaded. Not a problem if you don't intend to do autonomous missions right now.
</p>
</body>
</html>

View File

@ -0,0 +1,17 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Stabilization : Critical</h1>
<p>
One of the following conditions may be present:
<ul>
<li>Something is wrong with the Stabilization module</li>
<li>Waiting for good data from the Magnetometer or for GPS lock to perform module initialization.</li>
</ul>
</p>
</body>
</html>

View File

@ -7,7 +7,7 @@
<body>
<h1>Stack: Critical</h1>
<p>
Stack overflow
Stack overflow, stack alarms are due to module memory allocation being exceeded.
</p>
</body>
</html>
</html>

View File

@ -0,0 +1,19 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>System Configuration : Critical</h1>
<p>
One of the following conditions may be present:
<ul>
<li>
<p>You have set up a GPS mode (PosHold, RTB) to the flight mode switch, and you may have selected "Basic (Complementary)" fusion algorithm.</p>
<p> Select "GPS Navigation (INS13)" in Config -> Attitude Tab -> Parameters -> Attitude Estimation Algorithm.</p>
</li>
</ul>
</p>
</body>
</html>

View File

@ -7,7 +7,11 @@
<body>
<h1>Attitude : Critique</h1>
<p>
Cette alarme reste activée jusqu'à ce que des données soient reçues de l'accéléromètre.
Une des conditions suivantes semble présente :
<ul>
<li>Pas de données reçues en provenance des accéléromètres</li>
<li>En attente de données correctes du Magnétomètre ou d'une position GPS pour initialiser le module.</li>
</ul>
</p>
</body>
</html>

View File

@ -7,7 +7,11 @@
<body>
<h1>Attitude : Erreur</h1>
<p>
Echec de la récupération d'une mise à jour des accéléromètres ou des gyros.
Une des conditions suivantes semble présente :
<ul>
<li>Échec de l'acquisition en provenance des accéléromètres ou gyroscopes.</li>
<li>Algorithme d'évaluation de l'attitude réglé à "GPS Navigation (INS13)" et pas de magnétomètre : veuillez fixer la position Home.</li>
</ul>
</p>
</body>
</html>

View File

@ -5,9 +5,9 @@
<style></style>
</head>
<body>
<h1>Event System: Warning</h1>
<h1>Event System: Avertissement</h1>
<p>
There were problems with UAVObject events or callbacks
Il y a des problèmes avec un événement UAVObject ou des rappels
</p>
</body>
</html>
</html>

View File

@ -7,7 +7,7 @@
<body>
<h1>GPS: Avertissement</h1>
<p>
Le GPS a un fix et la navigation peut &ecirc;tre utilis&eacute;e. Cependant, la pr&eacute;cision de la position est tr&egrave;s faible (l'indication est &lt; &agrave; 7 satellites)
Le GPS a un fix et la navigation peut être utilisee. Cependant, la précision de la position est très faible (l'indication est < 7 satellites)
</p>
</body>
</html>

View File

@ -0,0 +1,18 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Magnétomètre : Critique</h1>
<p>
Des donnés proviennent du magnétomètre mais l'erreur est d'au moins 15%. Ceci peut être causé par :
</p>
<ul>
<li>Un magnétomètre qui n'a pas été calibré.</li>
<li>Quelque chose perturbe le magnétomètre. (Fort courant)</li>
</ul>
</p>
</body>
</html>

View File

@ -0,0 +1,13 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Magnétomètre : Avertissement</h1>
<p>
Le magnétomètre a une erreur de 5%
</p>
</body>
</html>

View File

@ -1,13 +0,0 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Mémoire : Critique</h1>
<p>
Either the remaining heap space or the IRQ stack has fallen below the <b>critical</b> limit (1000 bytes heap, 80 entries IRQ stack).
</p>
</body>
</html>

View File

@ -1,16 +0,0 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Mémoire : Avertissement</h1>
<p>
Either the remaining heap space or the IRQ stack has fallen below the <b>warning</b> limit (4000 bytes heap, 150 entries IRQ stack).
</p>
<p>
<b>Note:</b> if this is an original CC board (not CC3D or Revo), this condition is normal.
</p>
</body>
</html>

View File

@ -0,0 +1,17 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Mémoire : Critique</h1>
<p>
Soit l'espace mémoire ou la pile IRQ est passé en dessous de la limite <b>critique</b>.
</p>
<ul>
<li>Revo : 500 bytes heap, 80 entries IRQ stack.</li>
<li>CC/CC3D : 40 bytes heap, 60 entries IRQ stack.</li>
<ul>
</body>
</html>

View File

@ -0,0 +1,20 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Mémoire : Avertissement</h1>
<p>
Soit l'espace mémoire ou la pile IRQ est passé en dessous de la limite d'<b>avertissement</b>.
</p>
<ul>
<li>Revo : 1000 bytes heap, 150 entries IRQ stack.</li>
<li>CC/CC3D : 220 bytes heap, 100 entries IRQ stack.</li>
<ul>
<p>
<b>Note :</b> si vous avez une carte CC originale (pas CC3D ou Revo), cette situation est normale.
</p>
</body>
</html>

View File

@ -0,0 +1,13 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Pathplanner : Avertissement</h1>
<p>
Aucun chemin prédéfini téléversé. Ce n'est pas un problème si vous n'essayez pas de faire une mission automatique actuellement.
</p>
</body>
</html>

View File

@ -10,7 +10,7 @@
Une des conditions suivantes semble présente :
<ul>
<li>Le système est en mode failsafe.</li>
<li>Echec de la mise à jour d'un ou plusieurs des canaux d'accessoires.</li>
<li>Échec de la mise à jour d'un ou plusieurs des canaux d'accessoires.</li>
</ul>
</p>
</body>

View File

@ -0,0 +1,17 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Stabilisation : Critique</h1>
<p>
Une des conditions suivantes semble présente :
<ul>
<li>Quelque chose ne va pas avec le module de stabilisation</li>
<li>En attente de données correctes du Magnétomètre ou d'une position GPS pour initialiser le module.</li>
</ul>
</p>
</body>
</html>

View File

@ -0,0 +1,13 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Stack : Critique</h1>
<p>
Débordement de pile : cette alarme correspond à un dépassement de la mémoire allouée sur un module.
</p>
</body>
</html>

View File

@ -0,0 +1,19 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Configuration Système : Critique</h1>
<p>
Une des conditions suivantes semble présente :
<ul>
<li>
<p>Vous avez réglé un mode GPS (PosHold, RTB) l'interrupteur de mode de vol, et vous avez sélectionné "Basic (Complementary)" comme algorithme d'estimation de l'attitude.</p>
<p>Sélectionnez "GPS Navigation (INS13)" dans l'onglet Config -> Attitude -> Paramètres -> Algorithme d'Estimation de l'Attitude.</p>
</li>
</ul>
</p>
</body>
</html>

View File

@ -3,8 +3,8 @@
<file>html/Actuator-Critical.html</file>
<file>html/Receiver-Critical.html</file>
<file>html/Receiver-Warning.html</file>
<file>html/CPU-Critical.html</file>
<file>html/CPU-Warning.html</file>
<file>html/CPUOverload-Critical.html</file>
<file>html/CPUOverload-Warning.html</file>
<file>html/FlightTime-Error.html</file>
<file>html/Battery-Warning.html</file>
<file>html/BootFault-Critical.html</file>
@ -20,19 +20,24 @@
<file>html/GPS-Error.html</file>
<file>html/GPS-Warning.html</file>
<file>html/Guidance-Warning.html</file>
<file>html/Memory-Critical.html</file>
<file>html/Memory-Warning.html</file>
<file>html/OutOfMemory-Critical.html</file>
<file>html/OutOfMemory-Warning.html</file>
<file>html/Sensors-Critical.html</file>
<file>html/Stabilization-Warning.html</file>
<file>html/Stack-Critical.html</file>
<file>html/StackOverflow-Critical.html</file>
<file>html/Telemetry-Error.html</file>
<file>html/SystemConfiguration-Critical.html</file>
<file>html/PathPlan-Warning.html</file>
<file>html/Magnetometer-Critical.html</file>
<file>html/Magnetometer-Warning.html</file>
<file>html/Stabilization-Critical.html</file>
</qresource>
<qresource prefix="/systemhealth" lang="fr">
<file alias="html/Actuator-Critical.html">html/fr/Actuator-Critical.html</file>
<file alias="html/Receiver-Critical.html">html/fr/Receiver-Critical.html</file>
<file alias="html/Receiver-Warning.html">html/fr/Receiver-Warning.html</file>
<file alias="html/CPU-Critical.html">html/fr/CPU-Critical.html</file>
<file alias="html/CPU-Warning.html">html/fr/CPU-Warning.html</file>
<file alias="html/CPUOverload-Critical.html">html/fr/CPUOverload-Critical.html</file>
<file alias="html/CPUOverload-Warning.html">html/fr/CPUOverload-Critical.html</file>
<file alias="html/FlightTime-Error.html">html/fr/FlightTime-Error.html</file>
<file alias="html/Battery-Warning.html">html/fr/Battery-Warning.html</file>
<file alias="html/BootFault-Critical.html">html/fr/BootFault-Critical.html</file>
@ -48,12 +53,17 @@
<file alias="html/GPS-Error.html">html/fr/GPS-Error.html</file>
<file alias="html/GPS-Warning.html">html/fr/GPS-Warning.html</file>
<file alias="html/Guidance-Warning.html">html/fr/Guidance-Warning.html</file>
<file alias="html/Memory-Critical.html">html/fr/Memory-Critical.html</file>
<file alias="html/Memory-Warning.html">html/fr/Memory-Warning.html</file>
<file alias="html/OutOfMemory-Critical.html">html/fr/OutOfMemory-Critical.html</file>
<file alias="html/OutOfMemory-Warning.html">html/fr/OutOfMemory-Warning.html</file>
<file alias="html/Sensors-Critical.html">html/fr/Sensors-Critical.html</file>
<file alias="html/Stabilization-Warning.html">html/fr/Stabilization-Warning.html</file>
<file alias="html/Stack-Critical.html">html/fr/Stack-Critical.html</file>
<file alias="html/StackOverflow-Critical.html">html/fr/StackOverflow-Critical.html</file>
<file alias="html/Telemetry-Error.html">html/fr/Telemetry-Error.html</file>
<file alias="html/SystemConfiguration-Critical.html">html/fr/SystemConfiguration-Critical.html</file>
<file alias="html/PathPlan-Warning.html">html/fr/PathPlan-Warning.html</file>
<file alias="html/Magnetometer-Warning.html">html/fr/Magnetometer-Warning.html</file>
<file alias="html/Magnetometer-Critical.html">html/fr/Magnetometer-Critical.html</file>
<file alias="html/Stabilization-Critical.html">html/fr/Stabilization-Critical.html</file>
</qresource>
</RCC>

View File

@ -255,6 +255,7 @@ void SystemHealthGadgetWidget::showAlarmDescriptionForItemId(const QString itemI
if (alarmDescription.open(QIODevice::ReadOnly | QIODevice::Text)) {
QTextStream textStream(&alarmDescription);
textStream.setCodec("UTF-8");
QWhatsThis::showText(location, textStream.readAll());
}
}
@ -278,6 +279,7 @@ void SystemHealthGadgetWidget::showAllAlarmDescriptions(const QPoint & location)
QFile alarmDescription(":/systemhealth/html/" + elementId + ".html");
if (alarmDescription.open(QIODevice::ReadOnly | QIODevice::Text)) {
QTextStream textStream(&alarmDescription);
textStream.setCodec("UTF-8");
alarmsText.append(textStream.readAll());
}
}

View File

@ -86,7 +86,7 @@ while (1)
if (bufferlen < headerIdx + 12); break; end
sync = buffer(headerIdx);
% printf('%x ', sync);
headerIdx += 1;
headerIdx = headerIdx + 1;
if sync ~= correctSyncByte
wrongSyncByte = wrongSyncByte + 1;
continue
@ -99,7 +99,7 @@ while (1)
% get msg type (quint8 1 byte ) should be 0x20/0xA0, ignore the rest
msgType = buffer(headerIdx);
headerIdx += 1;
headerIdx = headerIdx + 1;
if msgType ~= correctMsgByte && msgType ~= correctTimestampedByte
% fixme: it should read the whole message payload instead of skipping and blindly searching for next sync byte.
fprintf('\nSkipping message type: %x \n', msgType);
@ -108,16 +108,16 @@ while (1)
% get msg size (quint16 2 bytes) excludes crc, include msg header and data payload
msgSize = uint32(typecast(buffer(headerIdx:headerIdx + 1), 'uint16'));
headerIdx += 2;
headerIdx = headerIdx + 2;
% get obj id (quint32 4 bytes)
objID = typecast(uint8(buffer(headerIdx:headerIdx + 3)), 'uint32');
headerIdx += 4;
headerIdx = headerIdx + 4;
% get instance id (quint16 2 bytes)
instID = typecast(uint8(buffer(headerIdx:headerIdx + 1)), 'uint16');
% printf('Id %x type %x size %u Inst %x ', objID, msgType, msgSize, instID);
headerIdx += 2;
headerIdx = headerIdx + 2;
% get timestamp if needed (quint32 4 bytes)
if msgType == correctMsgByte
@ -125,12 +125,12 @@ while (1)
elseif msgType == correctTimestampedByte
timestamp = typecast(uint8(buffer(headerIdx:headerIdx + 3)), 'uint32');
% printf('ts %u');
headerIdx += 4;
headerIdx = headerIdx + 4;
datasize = msgSize - headerLen - timestampLen;
end
% printf('\n');
bufferIdx = headerIdx;
headerIdx += datasize + crcLen + oplHeaderLen;
headerIdx = headerIdx + datasize + crcLen + oplHeaderLen;
%% Read object

View File

@ -27,6 +27,7 @@ OTHER_FILES += UAVObjects.pluginspec
# Add in all of the synthetic/generated uavobject files
HEADERS += \
$$UAVOBJECT_SYNTHETICS/vtolselftuningstats.h \
$$UAVOBJECT_SYNTHETICS/accelgyrosettings.h \
$$UAVOBJECT_SYNTHETICS/accessorydesired.h \
$$UAVOBJECT_SYNTHETICS/barosensor.h \
@ -82,6 +83,7 @@ HEADERS += \
$$UAVOBJECT_SYNTHETICS/pathdesired.h \
$$UAVOBJECT_SYNTHETICS/pathplan.h \
$$UAVOBJECT_SYNTHETICS/pathstatus.h \
$$UAVOBJECT_SYNTHETICS/pathsummary.h \
$$UAVOBJECT_SYNTHETICS/gpsvelocitysensor.h \
$$UAVOBJECT_SYNTHETICS/positionstate.h \
$$UAVOBJECT_SYNTHETICS/flightbatterystate.h \
@ -131,6 +133,7 @@ HEADERS += \
$$UAVOBJECT_SYNTHETICS/perfcounter.h
SOURCES += \
$$UAVOBJECT_SYNTHETICS/vtolselftuningstats.cpp \
$$UAVOBJECT_SYNTHETICS/accelgyrosettings.cpp \
$$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \
$$UAVOBJECT_SYNTHETICS/barosensor.cpp \
@ -186,6 +189,7 @@ SOURCES += \
$$UAVOBJECT_SYNTHETICS/pathdesired.cpp \
$$UAVOBJECT_SYNTHETICS/pathplan.cpp \
$$UAVOBJECT_SYNTHETICS/pathstatus.cpp \
$$UAVOBJECT_SYNTHETICS/pathsummary.cpp \
$$UAVOBJECT_SYNTHETICS/gpsvelocitysensor.cpp \
$$UAVOBJECT_SYNTHETICS/positionstate.cpp \
$$UAVOBJECT_SYNTHETICS/flightbatterystate.cpp \

View File

@ -1,7 +1,7 @@
# We use python to extract git version info and generate some other files,
# but it may be installed locally. The expected python version should be
# kept in sync with make/tools.mk.
PYTHON_DIR = qt-5.3.1/Tools/mingw482_32/opt/bin
PYTHON_DIR = qt-5.4.0/Tools/mingw491_32/opt/bin
ROOT_DIR = $$GCS_SOURCE_TREE/../..

View File

@ -74,12 +74,12 @@ ifeq ($(UNAME), Linux)
else ifeq ($(UNAME), Darwin)
ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-mac.tar.bz2
ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-mac.tar.bz2/+md5
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-mac-x64-clang-5.3.1.dmg
QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-mac-x64-clang-5.3.1.dmg.md5
QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.4/5.4.0/qt-opensource-mac-x64-clang-5.4.0.dmg
QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.4/5.4.0/qt-opensource-mac-x64-clang-5.4.0.dmg.md5
QT_SDK_ARCH := clang_64
QT_SDK_MAINTENANCE_TOOL := /Volumes/qt-opensource-mac-x64-clang-5.3.1/qt-opensource-mac-x64-clang-5.3.1.app/Contents/MacOS/qt-opensource-mac-x64-clang-5.3.1
QT_SDK_MOUNT_DIR := /Volumes/qt-opensource-mac-x64-clang-5.3.1
QT_SDK_INSTALLER_DAT := /Volumes/qt-opensource-mac-x64-clang-5.3.1/qt-opensource-mac-x64-clang-5.3.1.app/Contents/Resources/installer.dat
QT_SDK_MAINTENANCE_TOOL := /Volumes/qt-opensource-mac-x64-clang-5.4.0/qt-opensource-mac-x64-clang-5.4.0.app/Contents/MacOS/qt-opensource-mac-x64-clang-5.4.0
QT_SDK_MOUNT_DIR := /Volumes/qt-opensource-mac-x64-clang-5.4.0
QT_SDK_INSTALLER_DAT := /Volumes/qt-opensource-mac-x64-clang-5.4.0/qt-opensource-mac-x64-clang-5.4.0.app/Contents/Resources/installer.dat
UNCRUSTIFY_URL := http://wiki.openpilot.org/download/attachments/18612236/uncrustify-0.60.tar.gz
DOXYGEN_URL := http://wiki.openpilot.org/download/attachments/18612236/doxygen-1.8.3.1.src.tar.gz
else ifeq ($(UNAME), Windows)
@ -491,13 +491,15 @@ qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR)
$(V1) $(QT_SDK_MAINTENANCE_TOOL) --dump-binary-data -i $(QT_SDK_INSTALLER_DAT) -o $(1)
# Extract packages under tool directory
$(V1) $(MKDIR) -p $$(call toprel, $(dir $(2)))
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0qt-project-url.7z" | grep -v Extracting
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.3.1ThirdPartySoftware_Listing.7z" | grep -v Extracting
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0readme.7z" | grep -v Extracting
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_essentials.7z" | grep -v Extracting
# $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6).essentials/5.3.1icu_path_patcher.sh.7z" | grep -v Extracting
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_addons.7z" | grep -v Extracting
# go to OpenPilot/tools/5.3.1/gcc_64 and call patcher.sh
#$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0qt-project-url.7z" | grep -v Extracting
#$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.4.0ThirdPartySoftware_Listing.7z" | grep -v Extracting
#$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0readme.7z" | grep -v Extracting
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.54.$(6)/5.4.0-1qt5_essentials.7z" | grep -v Extracting
# $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.54.$(6).essentials/5.4.0icu_path_patcher.sh.7z" | grep -v Extracting
$(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.54.$(6)/5.4.0-1qt5_addons.7z" | grep -v Extracting
# go to OpenPilot/tools/5.4/gcc_64 and call patcher.sh
@$(ECHO)
@$(ECHO) "Running patcher in" $$(call toprel, $(QT_SDK_PREFIX))
$(V1) $(CD) $(QT_SDK_PREFIX)
@ -599,7 +601,7 @@ QT_BUILD_DIR := $(BUILD_DIR)/QT_BUILD
else ifeq ($(UNAME), Darwin)
QT_SDK_PREFIX := "$(QT_SDK_DIR)/5.3/$(QT_SDK_ARCH)"
QT_SDK_PREFIX := "$(QT_SDK_DIR)/5.4/$(QT_SDK_ARCH)"
QT_BUILD_DIR := $(BUILD_DIR)/QT_BUILD
$(eval $(call MAC_QT_INSTALL_TEMPLATE,$(QT_BUILD_DIR),$(QT_SDK_DIR),$(QT_SDK_URL),$(QT_SDK_MD5_URL),$(notdir $(QT_SDK_URL)),$(QT_SDK_ARCH)))

View File

@ -6,8 +6,6 @@ ifndef OPENPILOT_IS_COOL
$(error Top level Makefile must be used to build this target)
endif
FW_DIR := $(PACKAGE_DIR)/firmware
.PHONY: package
package:
( \
@ -17,6 +15,5 @@ package:
PACKAGE_DIR="$(PACKAGE_DIR)" \
PACKAGE_NAME="$(PACKAGE_NAME)" \
PACKAGE_SEP="$(PACKAGE_SEP)" \
FW_DIR="$(FW_DIR)" \
"$(ROOT_DIR)/package/osx/package" \
)

View File

@ -6,57 +6,22 @@ ifndef OPENPILOT_IS_COOL
$(error Top level Makefile must be used to build this target)
endif
FW_DIR := $(PACKAGE_DIR)/firmware
# Update this number for every formal release. The Deb packaging system relies on this to know to update a
# package or not. Otherwise, the user has to uninstall first.
# Until we do that, package name does NOT include $(VERNUM) and uses $(PACKAGE_LBL) only
VERNUM := 0.1.0
VERSION_FULL := $(VERNUM)-$(PACKAGE_LBL)
DEB_VER := $(PACKAGE_LBL)-1
DEB_DIR := $(ROOT_DIR)/package/linux/debian
DEB_BUILD_DIR := $(ROOT_DIR)/debian
SED_DATE_STRG = $(shell date -R)
SED_SCRIPT = s/<VERSION>/$(VERNUM)/;s/<DATE>/$(SED_DATE_STRG)/
SED_SCRIPT = s/<VERSION>/$(DEB_VER)/;s/<DATE>/$(SED_DATE_STRG)/
DEB_CFG_CMN := $(ROOT_DIR)/package/linux/deb_common
DEB_CFG_I386_DIR := $(ROOT_DIR)/package/linux/deb_i386
DEB_CFG_AMD64_DIR := $(ROOT_DIR)/package/linux/deb_amd64
DEB_CFG_CMN_FILES := $(shell ls $(DEB_CFG_CMN))
DEB_CFG_I386_FILES := $(shell ls $(DEB_CFG_I386_DIR))
DEB_CFG_AMD64_FILES := $(shell ls $(DEB_CFG_AMD64_DIR))
DEB_PLATFORM := amd64
DEB_MACHINE_DIR := $(DEB_CFG_AMD64_DIR)
DEB_MACHINE_FILES := $(DEB_CFG_AMD64_FILES)
MACHINE_TYPE := $(shell uname -m)
ifneq ($(MACHINE_TYPE), x86_64)
DEB_PLATFORM := i386
DEB_MACHINE_DIR := $(DEB_CFG_I386_DIR)
DEB_MACHINE_FILES := $(DEB_CFG_I386_FILES)
endif
DEB_PACKAGE_NAME := openpilot_$(VERNUM)_$(DEB_PLATFORM)
FULL_PACKAGE_NAME := $(PACKAGE_NAME)$(PACKAGE_SEP)$(PACKAGE_LBL)$(PACKAGE_SEP)$(DEB_PLATFORM)
ALL_DEB_FILES = $(foreach f, $(DEB_CFG_CMN_FILES), $(DEB_BUILD_DIR)/$(f))
ALL_DEB_FILES += $(foreach f, $(DEB_MACHINE_FILES), $(DEB_BUILD_DIR)/$(f))
DEB_ARCH := $(shell dpkg --print-architecture)
DEB_PACKAGE_NAME := openpilot_$(DEB_VER)_$(DEB_ARCH)
.PHONY: package
package: $(ALL_DEB_FILES)
package:
$(V1) echo "Building Linux package, please wait..."
$(V1) mkdir -p $(DEB_BUILD_DIR)
$(V1)$(shell echo $(FW_DIR) > $(BUILD_DIR)/package_dir)
$(V1) cp -rL $(DEB_DIR) $(DEB_BUILD_DIR)
$(V1)sed -i -e "$(SED_SCRIPT)" $(DEB_BUILD_DIR)/changelog
$(V1) cd .. && dpkg-buildpackage -b -us -uc
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).deb $(BUILD_DIR)/$(FULL_PACKAGE_NAME).deb
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(BUILD_DIR)/$(FULL_PACKAGE_NAME).changes
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).deb $(BUILD_DIR)/$(DEB_PACKAGE_NAME).deb
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(BUILD_DIR)/$(DEB_PACKAGE_NAME).changes
$(V1) rm -rf $(DEB_BUILD_DIR)
define CP_DEB_FILES_TEMPLATE
.PHONY: $(2)/$(1)
$(2)/$(1): $(3)/$(1)
$(V1) mkdir -p $(2)
$(V1) cp -a $$< $$@
endef
$(foreach cpfile, $(DEB_CFG_CMN_FILES), $(eval $(call CP_DEB_FILES_TEMPLATE,$(cpfile),$(DEB_BUILD_DIR),$(DEB_CFG_CMN))))
$(foreach cpfile, $(DEB_MACHINE_FILES), $(eval $(call CP_DEB_FILES_TEMPLATE,$(cpfile),$(DEB_BUILD_DIR),$(DEB_MACHINE_DIR))))

View File

@ -7,7 +7,6 @@ ifndef OPENPILOT_IS_COOL
endif
VERSION_CMD := $(VERSION_INFO)
FW_DIR := $(PACKAGE_DIR)/firmware
NSIS_OPTS := /V3
NSIS_WINX86 := $(ROOT_DIR)/package/winx86

View File

@ -1,15 +0,0 @@
Source: openpilot
Section: unknown
Priority: extra
Maintainer: naiiawah <naiiawah@openpilot.org>
Build-Depends: debhelper (>= 7.0.50~)
Standards-Version: 3.8.4
Homepage: http://www.openpilot.org
Vcs-Git: git://git.openpilot.org/OpenPilot.git
Vcs-Browser: http://git.openpilot.org/changelog/OpenPilot
Package: openpilot
Architecture: amd64
Depends: ${shlibs:Depends}, ${misc:Depends}
Description: OpenPilot GCS
OpenPilot Ground Control Station software

View File

@ -1,5 +0,0 @@
openpilot (<VERSION>) unstable; urgency=low
* Initial release (testing - unstable)
-- naiiawah <naiiawah@openpilot.org> <DATE>

View File

@ -1 +0,0 @@
7

View File

@ -1,154 +0,0 @@
#!/bin/sh
### BEGIN INIT INFO
# Provides: openpilot
# Required-Start: $network $local_fs
# Required-Stop:
# Default-Start: 2 3 4 5
# Default-Stop: 0 1 6
# Short-Description: <Enter a short description of the sortware>
# Description: <Enter a long description of the software>
# <...>
# <...>
### END INIT INFO
# Author: naiiawah <naiiawah@none>
# PATH should only include /usr/* if it runs after the mountnfs.sh script
PATH=/sbin:/usr/sbin:/bin:/usr/bin
DESC=openpilot # Introduce a short description here
NAME=openpilot # Introduce the short server's name here
DAEMON=/usr/sbin/openpilot # Introduce the server's location here
DAEMON_ARGS="" # Arguments to run the daemon with
PIDFILE=/var/run/$NAME.pid
SCRIPTNAME=/etc/init.d/$NAME
# Exit if the package is not installed
[ -x $DAEMON ] || exit 0
# Read configuration variable file if it is present
[ -r /etc/default/$NAME ] && . /etc/default/$NAME
# Load the VERBOSE setting and other rcS variables
. /lib/init/vars.sh
# Define LSB log_* functions.
# Depend on lsb-base (>= 3.0-6) to ensure that this file is present.
. /lib/lsb/init-functions
#
# Function that starts the daemon/service
#
do_start()
{
# Return
# 0 if daemon has been started
# 1 if daemon was already running
# 2 if daemon could not be started
start-stop-daemon --start --quiet --pidfile $PIDFILE --exec $DAEMON --test > /dev/null \
|| return 1
start-stop-daemon --start --quiet --pidfile $PIDFILE --exec $DAEMON -- \
$DAEMON_ARGS \
|| return 2
# Add code here, if necessary, that waits for the process to be ready
# to handle requests from services started subsequently which depend
# on this one. As a last resort, sleep for some time.
}
#
# Function that stops the daemon/service
#
do_stop()
{
# Return
# 0 if daemon has been stopped
# 1 if daemon was already stopped
# 2 if daemon could not be stopped
# other if a failure occurred
start-stop-daemon --stop --quiet --retry=TERM/30/KILL/5 --pidfile $PIDFILE --name $NAME
RETVAL="$?"
[ "$RETVAL" = 2 ] && return 2
# Wait for children to finish too if this is a daemon that forks
# and if the daemon is only ever run from this initscript.
# If the above conditions are not satisfied then add some other code
# that waits for the process to drop all resources that could be
# needed by services started subsequently. A last resort is to
# sleep for some time.
start-stop-daemon --stop --quiet --oknodo --retry=0/30/KILL/5 --exec $DAEMON
[ "$?" = 2 ] && return 2
# Many daemons don't delete their pidfiles when they exit.
rm -f $PIDFILE
return "$RETVAL"
}
#
# Function that sends a SIGHUP to the daemon/service
#
do_reload() {
#
# If the daemon can reload its configuration without
# restarting (for example, when it is sent a SIGHUP),
# then implement that here.
#
start-stop-daemon --stop --signal 1 --quiet --pidfile $PIDFILE --name $NAME
return 0
}
case "$1" in
start)
[ "$VERBOSE" != no ] && log_daemon_msg "Starting $DESC " "$NAME"
do_start
case "$?" in
0|1) [ "$VERBOSE" != no ] && log_end_msg 0 ;;
2) [ "$VERBOSE" != no ] && log_end_msg 1 ;;
esac
;;
stop)
[ "$VERBOSE" != no ] && log_daemon_msg "Stopping $DESC" "$NAME"
do_stop
case "$?" in
0|1) [ "$VERBOSE" != no ] && log_end_msg 0 ;;
2) [ "$VERBOSE" != no ] && log_end_msg 1 ;;
esac
;;
status)
status_of_proc "$DAEMON" "$NAME" && exit 0 || exit $?
;;
#reload|force-reload)
#
# If do_reload() is not implemented then leave this commented out
# and leave 'force-reload' as an alias for 'restart'.
#
#log_daemon_msg "Reloading $DESC" "$NAME"
#do_reload
#log_end_msg $?
#;;
restart|force-reload)
#
# If the "reload" option is implemented then remove the
# 'force-reload' alias
#
log_daemon_msg "Restarting $DESC" "$NAME"
do_stop
case "$?" in
0|1)
do_start
case "$?" in
0) log_end_msg 0 ;;
1) log_end_msg 1 ;; # Old process is still running
*) log_end_msg 1 ;; # Failed to start
esac
;;
*)
# Failed to stop
log_end_msg 1
;;
esac
;;
*)
#echo "Usage: $SCRIPTNAME {start|stop|restart|reload|force-reload}" >&2
echo "Usage: $SCRIPTNAME {start|stop|status|restart|force-reload}" >&2
exit 3
;;
esac
:

View File

@ -1,59 +0,0 @@
.\" Hey, EMACS: -*- nroff -*-
.\" First parameter, NAME, should be all caps
.\" Second parameter, SECTION, should be 1-8, maybe w/ subsection
.\" other parameters are allowed: see man(7), man(1)
.TH OPENPILOT SECTION "October 27, 2011"
.\" Please adjust this date whenever revising the manpage.
.\"
.\" Some roff macros, for reference:
.\" .nh disable hyphenation
.\" .hy enable hyphenation
.\" .ad l left justify
.\" .ad b justify to both left and right margins
.\" .nf disable filling
.\" .fi enable filling
.\" .br insert line break
.\" .sp <n> insert n+1 empty lines
.\" for manpage-specific macros, see man(7)
.SH NAME
openpilot \- program to do something
.SH SYNOPSIS
.B openpilot
.RI [ options ] " files" ...
.br
.B bar
.RI [ options ] " files" ...
.SH DESCRIPTION
This manual page documents briefly the
.B openpilot
and
.B bar
commands.
.PP
.\" TeX users may be more comfortable with the \fB<whatever>\fP and
.\" \fI<whatever>\fP escape sequences to invode bold face and italics,
.\" respectively.
\fBopenpilot\fP is a program that...
.SH OPTIONS
These programs follow the usual GNU command line syntax, with long
options starting with two dashes (`-').
A summary of options is included below.
For a complete description, see the Info files.
.TP
.B \-h, \-\-help
Show summary of options.
.TP
.B \-v, \-\-version
Show version of program.
.SH SEE ALSO
.BR bar (1),
.BR baz (1).
.br
The programs are documented fully by
.IR "The Rise and Fall of a Fooish Bar" ,
available via the Info system.
.SH AUTHOR
openpilot was written by <upstream author>.
.PP
This manual page was written by naiiawah <naiiawah@none>,
for the Debian project (and may be used by others).

View File

@ -1,154 +0,0 @@
<!doctype refentry PUBLIC "-//OASIS//DTD DocBook V4.1//EN" [
<!-- Process this file with docbook-to-man to generate an nroff manual
page: `docbook-to-man manpage.sgml > manpage.1'. You may view
the manual page with: `docbook-to-man manpage.sgml | nroff -man |
less'. A typical entry in a Makefile or Makefile.am is:
manpage.1: manpage.sgml
docbook-to-man $< > $@
The docbook-to-man binary is found in the docbook-to-man package.
Please remember that if you create the nroff version in one of the
debian/rules file targets (such as build), you will need to include
docbook-to-man in your Build-Depends control field.
-->
<!-- Fill in your name for FIRSTNAME and SURNAME. -->
<!ENTITY dhfirstname "<firstname>FIRSTNAME</firstname>">
<!ENTITY dhsurname "<surname>SURNAME</surname>">
<!-- Please adjust the date whenever revising the manpage. -->
<!ENTITY dhdate "<date>October 27, 2011</date>">
<!-- SECTION should be 1-8, maybe w/ subsection other parameters are
allowed: see man(7), man(1). -->
<!ENTITY dhsection "<manvolnum>SECTION</manvolnum>">
<!ENTITY dhemail "<email>naiiawah@none</email>">
<!ENTITY dhusername "naiiawah">
<!ENTITY dhucpackage "<refentrytitle>OPENPILOT</refentrytitle>">
<!ENTITY dhpackage "openpilot">
<!ENTITY debian "<productname>Debian</productname>">
<!ENTITY gnu "<acronym>GNU</acronym>">
<!ENTITY gpl "&gnu; <acronym>GPL</acronym>">
]>
<refentry>
<refentryinfo>
<address>
&dhemail;
</address>
<author>
&dhfirstname;
&dhsurname;
</author>
<copyright>
<year>2003</year>
<holder>&dhusername;</holder>
</copyright>
&dhdate;
</refentryinfo>
<refmeta>
&dhucpackage;
&dhsection;
</refmeta>
<refnamediv>
<refname>&dhpackage;</refname>
<refpurpose>program to do something</refpurpose>
</refnamediv>
<refsynopsisdiv>
<cmdsynopsis>
<command>&dhpackage;</command>
<arg><option>-e <replaceable>this</replaceable></option></arg>
<arg><option>--example <replaceable>that</replaceable></option></arg>
</cmdsynopsis>
</refsynopsisdiv>
<refsect1>
<title>DESCRIPTION</title>
<para>This manual page documents briefly the
<command>&dhpackage;</command> and <command>bar</command>
commands.</para>
<para>This manual page was written for the &debian; distribution
because the original program does not have a manual page.
Instead, it has documentation in the &gnu;
<application>Info</application> format; see below.</para>
<para><command>&dhpackage;</command> is a program that...</para>
</refsect1>
<refsect1>
<title>OPTIONS</title>
<para>These programs follow the usual &gnu; command line syntax,
with long options starting with two dashes (`-'). A summary of
options is included below. For a complete description, see the
<application>Info</application> files.</para>
<variablelist>
<varlistentry>
<term><option>-h</option>
<option>--help</option>
</term>
<listitem>
<para>Show summary of options.</para>
</listitem>
</varlistentry>
<varlistentry>
<term><option>-v</option>
<option>--version</option>
</term>
<listitem>
<para>Show version of program.</para>
</listitem>
</varlistentry>
</variablelist>
</refsect1>
<refsect1>
<title>SEE ALSO</title>
<para>bar (1), baz (1).</para>
<para>The programs are documented fully by <citetitle>The Rise and
Fall of a Fooish Bar</citetitle> available via the
<application>Info</application> system.</para>
</refsect1>
<refsect1>
<title>AUTHOR</title>
<para>This manual page was written by &dhusername; &dhemail; for
the &debian; system (and may be used by others). Permission is
granted to copy, distribute and/or modify this document under
the terms of the &gnu; General Public License, Version 2 any
later version published by the Free Software Foundation.
</para>
<para>
On Debian systems, the complete text of the GNU General Public
License can be found in /usr/share/common-licenses/GPL.
</para>
</refsect1>
</refentry>
<!-- Keep this comment at the end of the file
Local variables:
mode: sgml
sgml-omittag:t
sgml-shorttag:t
sgml-minimize-attributes:nil
sgml-always-quote-attributes:t
sgml-indent-step:2
sgml-indent-data:t
sgml-parent-document:nil
sgml-default-dtd-file:nil
sgml-exposed-tags:nil
sgml-local-catalogs:nil
sgml-local-ecat-files:nil
End:
-->

View File

@ -1,291 +0,0 @@
<?xml version='1.0' encoding='UTF-8'?>
<!DOCTYPE refentry PUBLIC "-//OASIS//DTD DocBook XML V4.5//EN"
"http://www.oasis-open.org/docbook/xml/4.5/docbookx.dtd" [
<!--
`xsltproc -''-nonet \
-''-param man.charmap.use.subset "0" \
-''-param make.year.ranges "1" \
-''-param make.single.year.ranges "1" \
/usr/share/xml/docbook/stylesheet/docbook-xsl/manpages/docbook.xsl \
manpage.xml'
A manual page <package>.<section> will be generated. You may view the
manual page with: nroff -man <package>.<section> | less'. A typical entry
in a Makefile or Makefile.am is:
DB2MAN = /usr/share/sgml/docbook/stylesheet/xsl/docbook-xsl/manpages/docbook.xsl
XP = xsltproc -''-nonet -''-param man.charmap.use.subset "0"
manpage.1: manpage.xml
$(XP) $(DB2MAN) $<
The xsltproc binary is found in the xsltproc package. The XSL files are in
docbook-xsl. A description of the parameters you can use can be found in the
docbook-xsl-doc-* packages. Please remember that if you create the nroff
version in one of the debian/rules file targets (such as build), you will need
to include xsltproc and docbook-xsl in your Build-Depends control field.
Alternatively use the xmlto command/package. That will also automatically
pull in xsltproc and docbook-xsl.
Notes for using docbook2x: docbook2x-man does not automatically create the
AUTHOR(S) and COPYRIGHT sections. In this case, please add them manually as
<refsect1> ... </refsect1>.
To disable the automatic creation of the AUTHOR(S) and COPYRIGHT sections
read /usr/share/doc/docbook-xsl/doc/manpages/authors.html. This file can be
found in the docbook-xsl-doc-html package.
Validation can be done using: `xmllint -''-noout -''-valid manpage.xml`
General documentation about man-pages and man-page-formatting:
man(1), man(7), http://www.tldp.org/HOWTO/Man-Page/
-->
<!-- Fill in your name for FIRSTNAME and SURNAME. -->
<!ENTITY dhfirstname "FIRSTNAME">
<!ENTITY dhsurname "SURNAME">
<!-- dhusername could also be set to "&dhfirstname; &dhsurname;". -->
<!ENTITY dhusername "naiiawah">
<!ENTITY dhemail "naiiawah@none">
<!-- SECTION should be 1-8, maybe w/ subsection other parameters are
allowed: see man(7), man(1) and
http://www.tldp.org/HOWTO/Man-Page/q2.html. -->
<!ENTITY dhsection "SECTION">
<!-- TITLE should be something like "User commands" or similar (see
http://www.tldp.org/HOWTO/Man-Page/q2.html). -->
<!ENTITY dhtitle "openpilot User Manual">
<!ENTITY dhucpackage "OPENPILOT">
<!ENTITY dhpackage "openpilot">
]>
<refentry>
<refentryinfo>
<title>&dhtitle;</title>
<productname>&dhpackage;</productname>
<authorgroup>
<author>
<firstname>&dhfirstname;</firstname>
<surname>&dhsurname;</surname>
<contrib>Wrote this manpage for the Debian system.</contrib>
<address>
<email>&dhemail;</email>
</address>
</author>
</authorgroup>
<copyright>
<year>2007</year>
<holder>&dhusername;</holder>
</copyright>
<legalnotice>
<para>This manual page was written for the Debian system
(and may be used by others).</para>
<para>Permission is granted to copy, distribute and/or modify this
document under the terms of the GNU General Public License,
Version 2 or (at your option) any later version published by
the Free Software Foundation.</para>
<para>On Debian systems, the complete text of the GNU General Public
License can be found in
<filename>/usr/share/common-licenses/GPL</filename>.</para>
</legalnotice>
</refentryinfo>
<refmeta>
<refentrytitle>&dhucpackage;</refentrytitle>
<manvolnum>&dhsection;</manvolnum>
</refmeta>
<refnamediv>
<refname>&dhpackage;</refname>
<refpurpose>program to do something</refpurpose>
</refnamediv>
<refsynopsisdiv>
<cmdsynopsis>
<command>&dhpackage;</command>
<!-- These are several examples, how syntaxes could look -->
<arg choice="plain"><option>-e <replaceable>this</replaceable></option></arg>
<arg choice="opt"><option>--example=<parameter>that</parameter></option></arg>
<arg choice="opt">
<group choice="req">
<arg choice="plain"><option>-e</option></arg>
<arg choice="plain"><option>--example</option></arg>
</group>
<replaceable class="option">this</replaceable>
</arg>
<arg choice="opt">
<group choice="req">
<arg choice="plain"><option>-e</option></arg>
<arg choice="plain"><option>--example</option></arg>
</group>
<group choice="req">
<arg choice="plain"><replaceable>this</replaceable></arg>
<arg choice="plain"><replaceable>that</replaceable></arg>
</group>
</arg>
</cmdsynopsis>
<cmdsynopsis>
<command>&dhpackage;</command>
<!-- Normally the help and version options make the programs stop
right after outputting the requested information. -->
<group choice="opt">
<arg choice="plain">
<group choice="req">
<arg choice="plain"><option>-h</option></arg>
<arg choice="plain"><option>--help</option></arg>
</group>
</arg>
<arg choice="plain">
<group choice="req">
<arg choice="plain"><option>-v</option></arg>
<arg choice="plain"><option>--version</option></arg>
</group>
</arg>
</group>
</cmdsynopsis>
</refsynopsisdiv>
<refsect1 id="description">
<title>DESCRIPTION</title>
<para>This manual page documents briefly the
<command>&dhpackage;</command> and <command>bar</command>
commands.</para>
<para>This manual page was written for the Debian distribution
because the original program does not have a manual page.
Instead, it has documentation in the GNU <citerefentry>
<refentrytitle>info</refentrytitle>
<manvolnum>1</manvolnum>
</citerefentry> format; see below.</para>
<para><command>&dhpackage;</command> is a program that...</para>
</refsect1>
<refsect1 id="options">
<title>OPTIONS</title>
<para>The program follows the usual GNU command line syntax,
with long options starting with two dashes (`-'). A summary of
options is included below. For a complete description, see the
<citerefentry>
<refentrytitle>info</refentrytitle>
<manvolnum>1</manvolnum>
</citerefentry> files.</para>
<variablelist>
<!-- Use the variablelist.term.separator and the
variablelist.term.break.after parameters to
control the term elements. -->
<varlistentry>
<term><option>-e <replaceable>this</replaceable></option></term>
<term><option>--example=<replaceable>that</replaceable></option></term>
<listitem>
<para>Does this and that.</para>
</listitem>
</varlistentry>
<varlistentry>
<term><option>-h</option></term>
<term><option>--help</option></term>
<listitem>
<para>Show summary of options.</para>
</listitem>
</varlistentry>
<varlistentry>
<term><option>-v</option></term>
<term><option>--version</option></term>
<listitem>
<para>Show version of program.</para>
</listitem>
</varlistentry>
</variablelist>
</refsect1>
<refsect1 id="files">
<title>FILES</title>
<variablelist>
<varlistentry>
<term><filename>/etc/foo.conf</filename></term>
<listitem>
<para>The system-wide configuration file to control the
behaviour of <application>&dhpackage;</application>. See
<citerefentry>
<refentrytitle>foo.conf</refentrytitle>
<manvolnum>5</manvolnum>
</citerefentry> for further details.</para>
</listitem>
</varlistentry>
<varlistentry>
<term><filename>${HOME}/.foo.conf</filename></term>
<listitem>
<para>The per-user configuration file to control the
behaviour of <application>&dhpackage;</application>. See
<citerefentry>
<refentrytitle>foo.conf</refentrytitle>
<manvolnum>5</manvolnum>
</citerefentry> for further details.</para>
</listitem>
</varlistentry>
</variablelist>
</refsect1>
<refsect1 id="environment">
<title>ENVIONMENT</title>
<variablelist>
<varlistentry>
<term><envar>FOO_CONF</envar></term>
<listitem>
<para>If used, the defined file is used as configuration
file (see also <xref linkend="files"/>).</para>
</listitem>
</varlistentry>
</variablelist>
</refsect1>
<refsect1 id="diagnostics">
<title>DIAGNOSTICS</title>
<para>The following diagnostics may be issued
on <filename class="devicefile">stderr</filename>:</para>
<variablelist>
<varlistentry>
<term><errortext>Bad configuration file. Exiting.</errortext></term>
<listitem>
<para>The configuration file seems to contain a broken configuration
line. Use the <option>--verbose</option> option, to get more info.
</para>
</listitem>
</varlistentry>
</variablelist>
<para><command>&dhpackage;</command> provides some return codes, that can
be used in scripts:</para>
<segmentedlist>
<segtitle>Code</segtitle>
<segtitle>Diagnostic</segtitle>
<seglistitem>
<seg><errorcode>0</errorcode></seg>
<seg>Program exited successfully.</seg>
</seglistitem>
<seglistitem>
<seg><errorcode>1</errorcode></seg>
<seg>The configuration file seems to be broken.</seg>
</seglistitem>
</segmentedlist>
</refsect1>
<refsect1 id="bugs">
<!-- Or use this section to tell about upstream BTS. -->
<title>BUGS</title>
<para>The program is currently limited to only work
with the <package>foobar</package> library.</para>
<para>The upstreams <acronym>BTS</acronym> can be found
at <ulink url="http://bugzilla.foo.tld"/>.</para>
</refsect1>
<refsect1 id="see_also">
<title>SEE ALSO</title>
<!-- In alpabetical order. -->
<para><citerefentry>
<refentrytitle>bar</refentrytitle>
<manvolnum>1</manvolnum>
</citerefentry>, <citerefentry>
<refentrytitle>baz</refentrytitle>
<manvolnum>1</manvolnum>
</citerefentry>, <citerefentry>
<refentrytitle>foo.conf</refentrytitle>
<manvolnum>5</manvolnum>
</citerefentry></para>
<para>The programs are documented fully by <citetitle>The Rise and
Fall of a Fooish Bar</citetitle> available via the <citerefentry>
<refentrytitle>info</refentrytitle>
<manvolnum>1</manvolnum>
</citerefentry> system.</para>
</refsect1>
</refentry>

View File

@ -1,2 +0,0 @@
?package(openpilot):needs="X11|text|vc|wm" section="Applications/see-menu-manual"\
title="openpilot" command="/usr/bin/openpilot"

View File

@ -1,4 +0,0 @@
#
# Regular cron jobs for the openpilot package
#
0 4 * * * root [ -x /usr/bin/openpilot_maintenance ] && /usr/bin/openpilot_maintenance

View File

@ -1,15 +0,0 @@
dh_prep
dh_installdirs
dh_installchangelogs
dh_installdocs
dh_installexamples
dh_installman
dh_link
dh_strip
dh_compress
dh_fixperms
dh_installdeb
dh_shlibdeps
dh_gencontrol
dh_md5sums
dh_builddeb

View File

@ -1,10 +0,0 @@
# Defaults for openpilot initscript
# sourced by /etc/init.d/openpilot
# installed at /etc/default/openpilot by the maintainer scripts
#
# This is a POSIX shell fragment
#
# Additional options that are passed to the Daemon.
DAEMON_OPTS=""

View File

@ -1,6 +0,0 @@
etc/xdg/menus/applications-merged
usr/share/applications
usr/share/pixmaps
usr/share/desktop-directories
usr/local/OpenPilot/firmware
usr/bin

View File

@ -1,20 +0,0 @@
Document: openpilot
Title: Debian openpilot Manual
Author: <insert document author here>
Abstract: This manual describes what openpilot is
and how it can be used to
manage online manuals on Debian systems.
Section: unknown
Format: debiandoc-sgml
Files: /usr/share/doc/openpilot/openpilot.sgml.gz
Format: postscript
Files: /usr/share/doc/openpilot/openpilot.ps.gz
Format: text
Files: /usr/share/doc/openpilot/openpilot.text.gz
Format: HTML
Index: /usr/share/doc/openpilot/html/index.html
Files: /usr/share/doc/openpilot/html/*.html

View File

@ -1,2 +0,0 @@
shlibs:Depends=libc6, libgcc1, libgl1-mesa-glx | libgl1, libglu1-mesa | libglu1, libsdl1.2debian, libstdc++6, libudev0 | libudev1, libusb-1.0-0
misc:Depends=

View File

@ -1,41 +0,0 @@
# Skip this section below if this device is not connected by USB
SUBSYSTEM!="usb", GOTO="op_rules_end"
# OpenPilot openpilot flight control board
SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4117", GOTO="op_rules"
SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415a", GOTO="op_rules"
# OpenPilot coptercontrol flight control board
SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415b", GOTO="op_rules"
# OpenPilot OPLink Mini radio modem board
SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415c", GOTO="op_rules"
# OpenPilot Revolution board
SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415e", GOTO="op_rules"
# Other OpenPilot reserved pids
SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415d", GOTO="op_rules"
SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4194", GOTO="op_rules"
SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4195", GOTO="op_rules"
# unprogrammed openpilot flight control board
SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5750", GOTO="op_rules"
# FTDI FT2232C Dual USB-UART/FIFO IC
SUBSYSTEM=="usb", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", GOTO="op_rules"
# Olimex Ltd. OpenOCD JTAG TINY
SUBSYSTEM=="usb", ATTRS{idVendor}=="15ba", ATTRS{idProduct}=="0004", GOTO="op_rules"
GOTO="op_rules_end"
LABEL="op_rules"
# Allow any seated user to access the board.
# uaccess: modern ACL-enabled udev
# udev-acl: for Ubuntu 12.10 and older
TAG+="uaccess", TAG+="udev-acl"
# Grant members of the "plugdev" group access to receiver (useful for SSH users)
#MODE="0664", GROUP="plugdev"
LABEL="op_rules_end"

View File

@ -1,39 +0,0 @@
#!/bin/sh
# postinst script for openpilot
#
# see: dh_installdeb(1)
set -e
# summary of how this script can be called:
# * <postinst> `configure' <most-recently-configured-version>
# * <old-postinst> `abort-upgrade' <new version>
# * <conflictor's-postinst> `abort-remove' `in-favour' <package>
# <new-version>
# * <postinst> `abort-remove'
# * <deconfigured's-postinst> `abort-deconfigure' `in-favour'
# <failed-install-package> <version> `removing'
# <conflicting-package> <version>
# for details, see http://www.debian.org/doc/debian-policy/ or
# the debian-policy package
case "$1" in
configure)
;;
abort-upgrade|abort-remove|abort-deconfigure)
;;
*)
echo "postinst called with unknown argument \`$1'" >&2
exit 1
;;
esac
# dh_installdeb will replace this with shell code automatically
# generated by other debhelper scripts.
#DEBHELPER#
exit 0

Some files were not shown because too many files have changed in this diff Show More