diff --git a/Makefile b/Makefile index a2d3d10f7..30e721747 100644 --- a/Makefile +++ b/Makefile @@ -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_ - Reformat code according to the project's standards" diff --git a/flight/libraries/inc/plans.h b/flight/libraries/inc/plans.h index fcf20a633..478de25af 100644 --- a/flight/libraries/inc/plans.h +++ b/flight/libraries/inc/plans.h @@ -30,6 +30,7 @@ #ifndef PLANS_H_ #define PLANS_H_ +#include #include /** \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 */ diff --git a/flight/libraries/inc/sanitycheck.h b/flight/libraries/inc/sanitycheck.h index 9576d1030..4c6d8e990 100644 --- a/flight/libraries/inc/sanitycheck.h +++ b/flight/libraries/inc/sanitycheck.h @@ -53,6 +53,6 @@ typedef enum { extern int32_t configuration_check(); -FrameType_t GetCurrentFrameType(); +extern FrameType_t GetCurrentFrameType(); #endif /* SANITYCHECK_H */ diff --git a/flight/libraries/paths.c b/flight/libraries/paths.c index 3bcd0a03d..cdfa27f04 100644 --- a/flight/libraries/paths.c +++ b/flight/libraries/paths.c @@ -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); diff --git a/flight/libraries/plans.c b/flight/libraries/plans.c index fda8b3f74..bf43d3d17 100644 --- a/flight/libraries/plans.c +++ b/flight/libraries/plans.c @@ -35,8 +35,11 @@ #include #include #include +#include +#include #include #include +#include #include #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); +} diff --git a/flight/libraries/sanitycheck.c b/flight/libraries/sanitycheck.c index 32f4e41e5..85c074ef9 100644 --- a/flight/libraries/sanitycheck.c +++ b/flight/libraries/sanitycheck.c @@ -36,6 +36,7 @@ #include #include #include +#include #include #include #include @@ -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 diff --git a/flight/modules/ManualControl/armhandler.c b/flight/modules/ManualControl/armhandler.c index 01f0eb84b..b17ce8334 100644 --- a/flight/modules/ManualControl/armhandler.c +++ b/flight/modules/ManualControl/armhandler.c @@ -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: diff --git a/flight/modules/ManualControl/manualcontrol.c b/flight/modules/ManualControl/manualcontrol.c index c695e5b43..fa8a7497d 100644 --- a/flight/modules/ManualControl/manualcontrol.c +++ b/flight/modules/ManualControl/manualcontrol.c @@ -37,22 +37,30 @@ #include #include #include +#include #include #include #include #include #include - +#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES +#include +#include +#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 */ + /** * @} * @} diff --git a/flight/modules/ManualControl/pathfollowerhandler.c b/flight/modules/ManualControl/pathfollowerhandler.c index b492f2281..fb0420317 100644 --- a/flight/modules/ManualControl/pathfollowerhandler.c +++ b/flight/modules/ManualControl/pathfollowerhandler.c @@ -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; diff --git a/flight/modules/ManualControl/stabilizedhandler.c b/flight/modules/ManualControl/stabilizedhandler.c index 085d349b4..4621a7171 100644 --- a/flight/modules/ManualControl/stabilizedhandler.c +++ b/flight/modules/ManualControl/stabilizedhandler.c @@ -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); } diff --git a/flight/modules/PathFollower/pathfollower.c b/flight/modules/PathFollower/pathfollower.c index 1cdcc569c..a9389db5b 100644 --- a/flight/modules/PathFollower/pathfollower.c +++ b/flight/modules/PathFollower/pathfollower.c @@ -54,6 +54,7 @@ #include #include #include +#include "plans.h" #include @@ -61,6 +62,7 @@ #include #include #include +#include #include #include #include @@ -73,25 +75,42 @@ #include #include #include +#include +#include // 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; diff --git a/flight/modules/Receiver/receiver.c b/flight/modules/Receiver/receiver.c index cf3230751..bf68b73e0 100644 --- a/flight/modules/Receiver/receiver.c +++ b/flight/modules/Receiver/receiver.c @@ -39,27 +39,33 @@ #include #include #include +#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES +#include +#endif #include #include #include + #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 + /** * @} * @} diff --git a/flight/pios/common/pios_rfm22b.c b/flight/pios/common/pios_rfm22b.c index 203fe1179..4aed541ed 100644 --- a/flight/pios/common/pios_rfm22b.c +++ b/flight/pios/common/pios_rfm22b.c @@ -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) diff --git a/flight/pios/stm32f10x/pios_dsm.c b/flight/pios/stm32f10x/pios_dsm.c index 577e22949..0a3450a9f 100644 --- a/flight/pios/stm32f10x/pios_dsm.c +++ b/flight/pios/stm32f10x/pios_dsm.c @@ -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); } diff --git a/flight/pios/stm32f4xx/pios_dsm.c b/flight/pios/stm32f4xx/pios_dsm.c index 314102c0e..055f9505c 100644 --- a/flight/pios/stm32f4xx/pios_dsm.c +++ b/flight/pios/stm32f4xx/pios_dsm.c @@ -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); } diff --git a/flight/pios/stm32f4xx/pios_ws2811.c b/flight/pios/stm32f4xx/pios_ws2811.c index 4b8e9d987..f0a9ddf29 100644 --- a/flight/pios/stm32f4xx/pios_ws2811.c +++ b/flight/pios/stm32f4xx/pios_ws2811.c @@ -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, diff --git a/flight/targets/boards/discoveryf4bare/firmware/UAVObjects.inc b/flight/targets/boards/discoveryf4bare/firmware/UAVObjects.inc index 9f2d3c902..9f4007db8 100644 --- a/flight/targets/boards/discoveryf4bare/firmware/UAVObjects.inc +++ b/flight/targets/boards/discoveryf4bare/firmware/UAVObjects.inc @@ -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 diff --git a/flight/targets/boards/revolution/board_hw_defs.c b/flight/targets/boards/revolution/board_hw_defs.c index 63b784f09..4d5b8aa22 100644 --- a/flight/targets/boards/revolution/board_hw_defs.c +++ b/flight/targets/boards/revolution/board_hw_defs.c @@ -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, diff --git a/flight/targets/boards/revolution/firmware/UAVObjects.inc b/flight/targets/boards/revolution/firmware/UAVObjects.inc index 9f2d3c902..9f4007db8 100644 --- a/flight/targets/boards/revolution/firmware/UAVObjects.inc +++ b/flight/targets/boards/revolution/firmware/UAVObjects.inc @@ -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 diff --git a/flight/targets/boards/revoproto/firmware/UAVObjects.inc b/flight/targets/boards/revoproto/firmware/UAVObjects.inc index 763b6d940..987266d1f 100644 --- a/flight/targets/boards/revoproto/firmware/UAVObjects.inc +++ b/flight/targets/boards/revoproto/firmware/UAVObjects.inc @@ -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 diff --git a/flight/targets/boards/simposix/firmware/UAVObjects.inc b/flight/targets/boards/simposix/firmware/UAVObjects.inc index 0db26345a..ab588c123 100644 --- a/flight/targets/boards/simposix/firmware/UAVObjects.inc +++ b/flight/targets/boards/simposix/firmware/UAVObjects.inc @@ -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 diff --git a/ground/openpilotgcs/openpilotgcs.pri b/ground/openpilotgcs/openpilotgcs.pri index 943dac262..e3da91f79 100644 --- a/ground/openpilotgcs/openpilotgcs.pri +++ b/ground/openpilotgcs/openpilotgcs.pri @@ -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 } diff --git a/ground/openpilotgcs/openpilotgcs.pro b/ground/openpilotgcs/openpilotgcs.pro index beedddc3c..aaf5edf05 100644 --- a/ground/openpilotgcs/openpilotgcs.pro +++ b/ground/openpilotgcs/openpilotgcs.pro @@ -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 { diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/AltitudeScale.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/AltitudeScale.qml index 52d6fd09c..35a57dba8 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/AltitudeScale.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/AltitudeScale.qml @@ -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 } diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Compass.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Compass.qml index 2fb92cc19..2340c74f5 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Compass.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Compass.qml @@ -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 diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Info.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Info.qml index 96897fc38..712fb3656 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Info.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Info.qml @@ -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 } } diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Panels.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Panels.qml index 537c4bbb4..ee885f643 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Panels.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Panels.qml @@ -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 } diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml index e14e4a96b..2b9aacb76 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Pfd.qml @@ -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) diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdIndicators.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdIndicators.qml index a254f231e..47f147e0e 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdIndicators.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/PfdIndicators.qml @@ -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 diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/SpeedScale.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/SpeedScale.qml index d86332410..a8b8153df 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/SpeedScale.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/SpeedScale.qml @@ -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 } diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/VsiScale.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/VsiScale.qml index 166f3bb22..0a177032d 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/VsiScale.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/VsiScale.qml @@ -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 } diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Warnings.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Warnings.qml index aa56d823f..8078a2854 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Warnings.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Warnings.qml @@ -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 } diff --git a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts index cf9877756..1cd212e60 100644 --- a/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts +++ b/ground/openpilotgcs/share/openpilotgcs/translations/openpilotgcs_fr.ts @@ -4393,8 +4393,7 @@ p, li { white-space: pre-wrap; } http://wiki.openpilot.org/x/OQBj - Lien Wiki FR - http://wiki.openpilot.org/x/hoBqAQ + @@ -4508,7 +4507,12 @@ p, li { white-space: pre-wrap; } Les paramètres importés ne sont pas compatibles avec ce plugin et ne seront pas importés ! - + + Unknown compatibility level: %1 + Niveau de compatibilité inconnu : %1 + + + WARNING: ATTENTION : @@ -4518,9 +4522,8 @@ p, li { white-space: pre-wrap; } ERREUR : - Unknown compatibility level: - Niveau de compatibilité inconnu : + Niveau de compatibilité inconnu : @@ -5233,8 +5236,7 @@ valeur. url:http://wiki.openpilot.org/display/Doc/Camera+Stabilization+Configuration - Lien Wiki FR - url:http://wiki.openpilot.org/x/UoHWAQ + @@ -6180,9 +6182,8 @@ p, li { white-space: pre-wrap; } Options de Configuration et Calibration - Manual Calibration - Calibration Manuelle + Calibration Manuelle @@ -6489,6 +6490,37 @@ Applique et Enregistre tous les paramètres sur la SD Start Transmitter Setup Wizard Démarrer l'Assistant Configuration Émetteur + + + Assisted Control stick deadband + Zone morte des manches - Pilotage assisté + + + + Assisted Control stick deadband in percents of full range (2-12) for use with GPSAssist. This can not be disabled. + Zone morte des manches du pilotage assisté en pourcentage du débattement maximum (2-12) pour utiliser GPSAssist. Ne peut être désactivé. + + + + Start Manual Calibration + Démarrer Calibration Manuelle + + + + Assisted Control + Pilotage Assisté + + + + <html><head/><body><p>Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.</p></body></html> + <html><head/><body><p>Les options du pilotage assisté améliorent le mode de vol courant. GPSAssist ajoute le freinage/maintien en position à la Stabilisation et PositionHold.</p></body></html> + + + + fieldname:FlightModeAssistMap + Do not translate ! + + MixerCurve @@ -7079,8 +7111,7 @@ Une valeur de 0.00 désactive le filtre. url:http://wiki.openpilot.org/display/Doc/Revolution+Manual+Sensor+Calibration - Lien Wiki FR - url:http://wiki.openpilot.org/x/FQWJAQ + @@ -7616,8 +7647,7 @@ value as the Kp. url:http://wiki.openpilot.org/x/DAO9 - Wiki FR - url:http://wiki.openpilot.org/x/d4BqAQ + @@ -8583,8 +8613,7 @@ uniquement lorsque le système est armé, sans désactiver le module. url:http://wiki.openpilot.org/x/DACiAQ - Wiki FR - url:http://wiki.openpilot.org/x/N4DWAQ + @@ -9098,7 +9127,7 @@ les données en cache Diagramme de Connexion - + Save File Enregistrer Fichier @@ -9323,6 +9352,16 @@ Veuillez sélectionner la configuration de voilure fixe désirée ci-dessous :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. Cette configuration concerne les ailes volantes, la dérive n'est pas encore supportée actuellement. La configuration s'applique à deux servos d'élevons, sans dérive. + + + Vtail + Vtail + + + + 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. + Cette configuration concerne un planeur classique utilisant deux servos d'ailerons indépendants ayant leur propre branchement (pas connectés avec un adaptateur en Y) plus un empenage en Vé avec mixage profondeur/direction. + HeliPage @@ -9435,17 +9474,15 @@ p, li { white-space: pre-wrap; } 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 été l'une des premières à être utilisée et est encore utilisée pour le vol sportif. Cette agencement n'est pas bien adapté pour que FPV car le moteur de devant a tendance à être dans le champ de vision de la caméra. - Quadcopter H - Quadricoptère H + Quadricoptère H - Quadcopter H, Blackout miniH - Quadricoptère H, blackout miniH + Quadricoptère H, blackout miniH - + Hexacopter Hexacoptère @@ -9480,7 +9517,7 @@ p, li { white-space: pre-wrap; } Hexacoptère X - + OpenPilot Multirotor Configuration Configuration Multirotor OpenPilot @@ -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 : - + Hexacopter H Hexacoptère H @@ -9527,7 +9564,7 @@ Veuillez sélectionner le type de multirotor désiré pour la configuration ci-d - + Start Démarrer @@ -9760,6 +9797,50 @@ p, li { white-space: pre-wrap; } <html><head/><body><p align="center"><span style=" font-family:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;">The Surface Vehicle section of the OpenPilot Setup Wizard is not yet implemented</span><br/></p></body></html> <html><head/><body><p align="center"><span style=" font-family:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;">La partie Véhicule roulant de l'Assistant de Configuration OpenPilot n'est pas encore implémentée</span><br/></p></body></html> + + + OpenPilot Ground Vehicle Configuration + Configuration Véhicule Terrestre OpenPilot + + + + 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: + Cette partie de l'assistant va permettre le configuration du contrôleur OpenPilot pour fonctionner avec des véhicules terrestres utilisant plusieurs moteurs/servos. L'assistant supporte les types de configurations les plus courants. D'autres variantes de véhicules peuvent être configurées dans l'onglet "Véhicule" > "Personnalisé" du plugin de configuration de GCS. + +Veuillez sélectionner le type de véhicule terrestre dont vous voulez créer la configuration ci-dessous : + + + + Car + Voiture + + + + This setup expects a traditional car with a rear motor and a front streering servo + Cette configuration correspond à une voiture classique avec un moteur à l'arrière et un servo de direction à l'avant + + + + Tank + Tank + + + + This setup expects a traditional vehicle using only two motors and differential steering + Cette configuration correspond à une véhicule classique utilisant deux moteurs et une direction par différentiel entre ces moteurs + + + + Motorcycle + Motocycle + + + + This setup currently expects a motorcyle setup, using one motor and one servo for steering. + Cette configuration correspond à une moto utilisant un moteur et un servo pour la direction. + VehiclePage @@ -9898,8 +9979,7 @@ persistant de la carte, et ensuite ferme la boite de dialogue. http://wiki.openpilot.org/display/Doc/UAV+Settings+import-export - Lien Wiki FR - http://wiki.openpilot.org/x/IQCJAQ + @@ -10417,8 +10497,7 @@ p, li { white-space: pre-wrap; } http://wiki.openpilot.org/x/D4AUAQ - Lien Wiki FR - http://wiki.openpilot.org/x/HoBqAQ + @@ -10431,8 +10510,7 @@ p, li { white-space: pre-wrap; } http://wiki.openpilot.org/x/44Cf - Lien Wiki FR - http://wiki.openpilot.org/x/IIBqAQ + @@ -10453,26 +10531,24 @@ Voulez-vous toujours continuer ? ConfigInputWidget - + http://wiki.openpilot.org/x/04Cf - Lien Wiki FR - http://wiki.openpilot.org/x/aIBqAQ + - Arming Settings are now set to 'Always Disarmed' for your safety. Contexte : Onglet "Paramètres d'Armement" Pour des raisons de sécurité les Paramètres d'Armement ont été modifiés à 'Toujours Désarmé'. - + 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. redirigé vers / sur ? Vous devrez reconfigurer manuellement les paramètres d'armement lorsque l'assistant sera terminé. Après la dernière étape de l'assistant, vous serez redirigé vers l'écran des Paramètres d'Armement. - + Next Suivant @@ -10668,9 +10744,28 @@ Bougez le manche %1. Vous avez la possibilité d'appuyer sur Suivant pour ignorer ce canal. - + + Stop Manual Calibration + Arrêter Calibration Manuelle + + + + <p>Arming Settings are now set to 'Always Disarmed' for your safety.</p><p>Be sure your receiver is powered with an external source and Transmitter is on.</p><p align='center'><b>Stop Manual Calibration</b> when done</p> + <p>Pour des raisons de sécurité les Paramètres d'Armement ont été modifiés à 'Toujours Désarmé'.</p><p>Veuillez vérifier que votre récepteur est alimenté avec une source externe et que la radio Rx est allumée. <p align='center'><b>Arrêter Calibration Manuelle</b> à la fin</p> + + + + You will have to reconfigure the arming settings manually when the manual calibration is finished. + Vous devrez reconfigurer les paramètres d'armement manuellement lorsque la calibration manuelle sera terminée. + + + + Start Manual Calibration + Démarrer Calibration Manuelle + + You will have to reconfigure the arming settings manually when the wizard is finished. - Vous devrez reconfigurer les paramètres d'armement manuellement lorsque l'assistant sera terminé. + Vous devrez reconfigurer les paramètres d'armement manuellement lorsque l'assistant sera terminé. @@ -10950,12 +11045,27 @@ Bougez le manche %1. ScopeGadgetWidget - + Click legend to show/hide scope trace. Double click legend or plot to show/hide legend. 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. + + + Clear + Effacer + + + + Copy to Clipboard + Copier dans le Presse-papiers + + + + Options... + Options... + SetupWizard @@ -10965,7 +11075,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Assistant Configuration OpenPilot - + Controller type: Type de contrôleur : @@ -11001,18 +11111,19 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende. - + - + + - + Unknown Inconnu - + Vehicle type: Type de véhicule : @@ -11023,12 +11134,13 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende. - + + Vehicle sub type: Sous-type véhicule : - + Tricopter Tricoptère @@ -11043,9 +11155,8 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Quadricoptère + - Quadcopter H - Quadricoptère H + Quadricoptère H @@ -11118,7 +11229,22 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Véhicule surface - + + Car + Voiture + + + + Tank + Tank + + + + Motorcycle + Motocycle + + + Input type: Type d'entrée : @@ -11140,7 +11266,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende. Spektrum Satellite - + @@ -11158,7 +11284,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Contrôleur Rapide (%1 Hz) - + Servo type: Type Servo : @@ -11258,7 +11384,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende. Writing Airspeed sensor settings - Écriture paramètres capteur Vitesse Air + Écriture paramètres capteur Vitesse Air @@ -11266,13 +11392,14 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Écriture paramètres matériels - + + Writing actuator settings Écriture paramètres actionneurs - + Writing flight mode settings 1/2 Écriture paramètres mode de vol 1/2 @@ -11298,7 +11425,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende.Écriture paramètres de stabilisation - + Writing mixer settings Écriture paramètres mixeur @@ -11534,8 +11661,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende. http://wiki.openpilot.org/display/Doc/Erase+board+settings - Wiki FR - Uploader - http://wiki.openpilot.org/x/SYBqAQ + @@ -11639,8 +11765,7 @@ Double clic sur la légende ou le tracé pour afficher/cacher la légende. http://wiki.openpilot.org/x/AoBZ - Lien Wiki FR - http://wiki.openpilot.org/x/SYBqAQ + @@ -12256,39 +12381,32 @@ La carte sera redémarrée et tous les paramètres effacés. Affectations sorties - Engine - Moteur + Moteur - Select output channel for the engine - Sélectionner le canal de sortie pour le moteur + Sélectionner le canal de sortie pour le moteur - Aileron 1 - Aileron 1 + Aileron 1 - Select output channel for the first aileron (or elevon) - Sélectionner le canal de sortie pour le premier aileron (ou élevon) + Sélectionner le canal de sortie pour le premier aileron (ou élevon) - Aileron 2 - Aileron 2 + Aileron 2 - Select output channel for the second aileron (or elevon) - Sélectionner le canal de sortie pour le second aileron (ou élevon) + Sélectionner le canal de sortie pour le second aileron (ou élevon) - Motor - Moteur + Moteur @@ -12360,6 +12478,16 @@ La carte sera redémarrée et tous les paramètres effacés. Mixer OK + + + Motor 1 + Moteur 1 + + + + Vehicle frame + + MultiRotorConfigWidget @@ -12943,8 +13071,7 @@ Méfiez-vous de ne pas vous verrouiller l'accès ! url:http://wiki.openpilot.org/x/hgAGAQ - Lien Wiki FR - url:http://wiki.openpilot.org/x/B4BYAQ + @@ -13130,8 +13257,7 @@ p, li { white-space: pre-wrap; } http://wiki.openpilot.org/x/WIGf - Lien Wiki FR - http://wiki.openpilot.org/x/aoBqAQ + @@ -13144,8 +13270,7 @@ p, li { white-space: pre-wrap; } http://wiki.openpilot.org/x/GgDBAQ - Lien Wiki FR - http://wiki.openpilot.org/x/TYRNAQ + @@ -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. - + Chan %1 Canal %1 @@ -14276,6 +14401,16 @@ et même conduire au crash. A utiliser avec prudence. Text Texte + + + Channel value + Valeur canal + + + + Channel Value + Valeur Canal + ConfigVehicleTypeWidget @@ -14307,8 +14442,7 @@ et même conduire au crash. A utiliser avec prudence. http://wiki.openpilot.org/x/44Cf - Lien Wiki FR - http://wiki.openpilot.org/x/IIBqAQ + @@ -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'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'êtes pas en mesure d'en choisir un, sélectionnez l'élément générique de la liste. - + Current Tuning Réglages Actuels @@ -15011,9 +15145,8 @@ p, li { white-space: pre-wrap; } Multirotor - Quadricoptère X - Multirotor - Quadrocopter H - Multirotor - Quadricoptère H + Multirotor - Quadricoptère H diff --git a/ground/openpilotgcs/src/libs/qwt/src/src.pro b/ground/openpilotgcs/src/libs/qwt/src/src.pro index 6123541e3..fcdf13f5f 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/src.pro +++ b/ground/openpilotgcs/src/libs/qwt/src/src.pro @@ -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 diff --git a/ground/openpilotgcs/src/openpilotgcslibrary.pri b/ground/openpilotgcs/src/openpilotgcslibrary.pri index 59791944d..4dbe647f5 100644 --- a/ground/openpilotgcs/src/openpilotgcslibrary.pri +++ b/ground/openpilotgcs/src/openpilotgcslibrary.pri @@ -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 diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index d7b9fd7d0..e6256cf98 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -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); } diff --git a/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp index 6595b6366..684f32b78 100644 --- a/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp @@ -32,6 +32,12 @@ #include #include +// 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)"); +} + /** @} @} diff --git a/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.h b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.h index 986f7c7bd..bd2ebd0bf 100644 --- a/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configpipxtremewidget.h @@ -62,6 +62,9 @@ private slots: void disconnected(); void bind(); void ppmOnlyChanged(); + void minChannelChanged(); + void maxChannelChanged(); + void channelChanged(bool isMax); }; #endif // CONFIGTXPIDWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index dbf637b81..1cc129bde 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -6,8 +6,8 @@ 0 0 - 796 - 591 + 1250 + 755 @@ -234,6 +234,29 @@ + + + + Assisted Control stick deadband + + + + + + + Assisted Control stick deadband in percents of full range (2-12) for use with GPSAssist. This can not be disabled. + + + 1 + + + 2.000000000000000 + + + 12.000000000000000 + + + @@ -1206,197 +1229,6 @@ font:bold; 6 - - - - - 80 - 20 - - - - - 16777215 - 20 - - - - 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; - - - Settings Bank - - - Qt::AlignCenter - - - - - - - - 138 - 20 - - - - - 16777215 - 20 - - - - 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; - - - Flight Mode Count - - - Qt::AlignCenter - - - - - - - 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. - - - 1 - - - 6 - - - 3 - - - - - - - - 0 - 0 - - - - - 10 - 75 - true - - - - <html><head/><body><p>Avoid &quot;Manual&quot; for multirotors! Never select &quot;Altitude&quot;, &quot;VelocityControl&quot; or &quot;CruiseControl&quot; on a fixed wing!</p></body></html> - - - Qt::AlignCenter - - - true - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 20 - - - - - - - - Qt::Vertical - - - - - - - - 138 - 20 - - - - - 16777215 - 20 - - - - 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; - - - Flight Mode - - - Qt::AlignCenter - - - @@ -1941,6 +1773,418 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread + + + + + 138 + 20 + + + + + 16777215 + 20 + + + + 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; + + + Settings Bank + + + Qt::AlignCenter + + + + + + + + 138 + 20 + + + + + 16777215 + 20 + + + + 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; + + + Flight Mode Count + + + Qt::AlignCenter + + + + + + + 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. + + + 1 + + + 6 + + + 3 + + + + + + + + 0 + 0 + + + + + 10 + 75 + true + + + + <html><head/><body><p>Avoid &quot;Manual&quot; for multirotors! Never select &quot;Altitude&quot;, &quot;VelocityControl&quot; or &quot;CruiseControl&quot; on a fixed wing!</p></body></html> + + + Qt::AlignCenter + + + true + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 20 + + + + + + + + Qt::Vertical + + + + + + + + 138 + 20 + + + + + 16777215 + 20 + + + + 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; + + + Flight Mode + + + Qt::AlignCenter + + + + + + + + 138 + 0 + + + + Qt::LeftToRight + + + 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; + + + Assisted Control + + + Qt::AlignCenter + + + + + + + + 75 + 0 + + + + QFrame::NoFrame + + + QFrame::Plain + + + + 1 + + + 1 + + + 1 + + + 1 + + + + + + 75 + 0 + + + + Qt::StrongFocus + + + <html><head/><body><p>Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.</p></body></html> + + + + objname:StabilizationSettings + fieldname:FlightModeAssistMap + index:0 + haslimits:no + scale:1 + buttongroup:16 + + + + + + + + + 75 + 0 + + + + Qt::StrongFocus + + + <html><head/><body><p>Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.</p></body></html> + + + + objname:StabilizationSettings + fieldname:FlightModeAssistMap + index:1 + haslimits:no + scale:1 + buttongroup:16 + + + + + + + + + 75 + 0 + + + + Qt::StrongFocus + + + <html><head/><body><p>Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.</p></body></html> + + + + objname:StabilizationSettings + fieldname:FlightModeAssistMap + index:2 + haslimits:no + scale:1 + buttongroup:16 + + + + + + + + false + + + + 75 + 0 + + + + Qt::StrongFocus + + + <html><head/><body><p>Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.</p></body></html> + + + + objname:StabilizationSettings + fieldname:FlightModeAssistMap + index:3 + haslimits:no + scale:1 + buttongroup:16 + + + + + + + + false + + + + 75 + 0 + + + + Qt::StrongFocus + + + <html><head/><body><p>Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.</p></body></html> + + + + objname:StabilizationSettings + fieldname:FlightModeAssistMap + index:4 + haslimits:no + scale:1 + buttongroup:16 + + + + + + + + false + + + + 75 + 0 + + + + Qt::StrongFocus + + + <html><head/><body><p>Assisted Control options augment the primary flight mode. GPSAssist adds brake/hold to Stabilization and PositionHold.</p></body></html> + + + + objname:StabilizationSettings + fieldname:FlightModeAssistMap + index:5 + haslimits:no + scale:1 + buttongroup:16 + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui index baa3482c2..9cbe0265c 100644 --- a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui +++ b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui @@ -6,7 +6,7 @@ 0 0 - 834 + 971 652 @@ -49,8 +49,8 @@ 0 0 - 810 - 575 + 949 + 558 @@ -72,14 +72,14 @@ Configuration - + Com speed in bps. - + @@ -95,7 +95,7 @@ - + @@ -111,7 +111,7 @@ - + @@ -124,7 +124,7 @@ - + @@ -140,7 +140,7 @@ - + @@ -153,7 +153,20 @@ - + + + + + 16777215 + 16777215 + + + + Choose the function for the USB virtual com port + + + + @@ -172,7 +185,7 @@ - + @@ -188,20 +201,10 @@ - - - - - 16777215 - 16777215 - - - - Choose the function for the USB virtual com port - - + + - + @@ -217,10 +220,29 @@ - - + + + + + 60 + 16777215 + + + + + 50 + false + + + + Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. + + + 250 + + - + @@ -252,22 +274,6 @@ - - - - - 50 - false - - - - Channel 0 is 430 MHz, channel 249 is 440 MHz, and the channel spacing is 40 KHz. - - - 249 - - - @@ -286,6 +292,12 @@ + + + 60 + 16777215 + + 50 @@ -293,10 +305,10 @@ - Channel 0 is 430 MHz, channel 249 is 440 MHz, and the channel spacing is 40 KHz. + Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. - 249 + 250 @@ -318,6 +330,12 @@ + + + 60 + 16777215 + + 50 @@ -328,7 +346,68 @@ Sets the random sequence of channels to use for frequency hopping. - 249 + 250 + + + + + + + + 50 + false + + + + This modem will be a coordinator and other modems will bind to it. + + + Coordinator + + + + + + + + 110 + 16777215 + + + + 440.000 (MHz) + + + + + + + + 110 + 16777215 + + + + 430.000 (MHz) + + + + + + + + 50 + false + + + + false + + + If selected, data will only be transmitted from the coordinator to the Rx modem. + + + One-Way @@ -349,22 +428,6 @@ - - - - 50 - false - - - - If selected, data will only be transmitted from the coordinator to the Rx modem. - - - One-Way - - - - @@ -380,22 +443,6 @@ - - - - - 50 - false - - - - This modem will be a coordinator and other modems will bind to it. - - - Coordinator - - - diff --git a/ground/openpilotgcs/src/plugins/pfdqml/PfdResources.qrc b/ground/openpilotgcs/src/plugins/pfdqml/PfdResources.qrc new file mode 100644 index 000000000..5c802bcc5 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/PfdResources.qrc @@ -0,0 +1,5 @@ + + + fonts/PTS75F.ttf + + diff --git a/ground/openpilotgcs/src/plugins/pfdqml/fonts/PTS75F.ttf b/ground/openpilotgcs/src/plugins/pfdqml/fonts/PTS75F.ttf new file mode 100644 index 000000000..dbf45b59a Binary files /dev/null and b/ground/openpilotgcs/src/plugins/pfdqml/fonts/PTS75F.ttf differ diff --git a/ground/openpilotgcs/src/plugins/pfdqml/fonts/Paratype PT Sans Free Font License.txt b/ground/openpilotgcs/src/plugins/pfdqml/fonts/Paratype PT Sans Free Font License.txt new file mode 100644 index 000000000..20330f6d1 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/pfdqml/fonts/Paratype PT Sans Free Font License.txt @@ -0,0 +1,26 @@ +Copyright © 2009 ParaType Ltd. +with Reserved Names &quot;PT Sans&quot; and &quot;ParaType&quot;. + +FONT LICENSE + +PERMISSION &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; 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 &quot;AS IS&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 \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro b/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro index 0d7da9e26..5c532a3c9 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqml.pro @@ -40,3 +40,6 @@ OTHER_FILES += PfdQml.pluginspec FORMS += pfdqmlgadgetoptionspage.ui +RESOURCES += \ + PfdResources.qrc + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp index 897568c52..20b1d9887 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -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; } diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/Attitude-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/Attitude-Critical.html index 58c622501..b7676c6dd 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/Attitude-Critical.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/Attitude-Critical.html @@ -5,9 +5,13 @@ -

Attitude: Critical

+

Attitude : Critical

- This alarm will remain set until data is received from the accelerometer. + One of the following conditions may be present: +

    +
  • No data is received from the accelerometer
  • +
  • Waiting for good data from Magnetometer or GPS lock to perform module initialization.
  • +

- \ No newline at end of file + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/Attitude-Error.html b/ground/openpilotgcs/src/plugins/systemhealth/html/Attitude-Error.html index 826e29d7c..d1cbb4982 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/Attitude-Error.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/Attitude-Error.html @@ -5,9 +5,13 @@ -

Attitude: Error

+

Attitude : Error

- Failed to get an update from the accelerometer or gyros. + One of the following conditions may be present: +

    +
  • Failed to get an update from the accelerometer or gyros.
  • +
  • Attitude Estimation Algorithm set to "GPS Navigation (INS13)" and no Magnetometer : please set HomeLocation.
  • +

- \ No newline at end of file + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/CPU-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/CPUOverload-Critical.html similarity index 95% rename from ground/openpilotgcs/src/plugins/systemhealth/html/CPU-Critical.html rename to ground/openpilotgcs/src/plugins/systemhealth/html/CPUOverload-Critical.html index 273423124..a3b0e5a74 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/CPU-Critical.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/CPUOverload-Critical.html @@ -10,4 +10,4 @@ CPU load has exceeded 95%

- \ No newline at end of file + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/CPU-Warning.html b/ground/openpilotgcs/src/plugins/systemhealth/html/CPUOverload-Warning.html similarity index 95% rename from ground/openpilotgcs/src/plugins/systemhealth/html/CPU-Warning.html rename to ground/openpilotgcs/src/plugins/systemhealth/html/CPUOverload-Warning.html index a6c15546d..5c2d4639f 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/CPU-Warning.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/CPUOverload-Warning.html @@ -10,4 +10,4 @@ CPU load has exceeded 80%

- \ No newline at end of file + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/Magnetometer-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/Magnetometer-Critical.html new file mode 100644 index 000000000..ede2a0b62 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/Magnetometer-Critical.html @@ -0,0 +1,18 @@ + + + + + + + +

Magnetometer : Critical

+

+ Data is coming from the magnetometer, but the readings are off by over 15%. This can be caused by various reasons: +

+
    +
  • Magnetometer has not been calibrated.
  • +
  • Something is interfering with the magnetometer. (High current)
  • +
+

+ + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/Stack-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/Magnetometer-Warning.html similarity index 57% rename from ground/openpilotgcs/src/plugins/systemhealth/html/Stack-Critical.html rename to ground/openpilotgcs/src/plugins/systemhealth/html/Magnetometer-Warning.html index ad5e8c7ef..9e8a1a5ae 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/Stack-Critical.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/Magnetometer-Warning.html @@ -5,9 +5,9 @@ -

Stack: Critical

+

Magnetometer : Warning

- Stack overflow + Magnetometer readings are off by over 5%

- \ No newline at end of file + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/Memory-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/OutOfMemory-Critical.html similarity index 54% rename from ground/openpilotgcs/src/plugins/systemhealth/html/Memory-Critical.html rename to ground/openpilotgcs/src/plugins/systemhealth/html/OutOfMemory-Critical.html index b1fa75164..892c338e8 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/Memory-Critical.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/OutOfMemory-Critical.html @@ -7,7 +7,11 @@

Memory: Critical

- Either the remaining heap space or the IRQ stack has fallen below the critical limit (1000 bytes heap, 80 entries IRQ stack). + Either the remaining heap space or the IRQ stack has fallen below the critical limit.

+
    +
  • Revo : 500 bytes heap, 80 entries IRQ stack.
  • +
  • CC/CC3D : 40 bytes heap, 60 entries IRQ stack.
  • +
      - \ No newline at end of file + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/Memory-Warning.html b/ground/openpilotgcs/src/plugins/systemhealth/html/OutOfMemory-Warning.html similarity index 72% rename from ground/openpilotgcs/src/plugins/systemhealth/html/Memory-Warning.html rename to ground/openpilotgcs/src/plugins/systemhealth/html/OutOfMemory-Warning.html index e4ebf94a6..3a2e6ded9 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/Memory-Warning.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/OutOfMemory-Warning.html @@ -9,8 +9,12 @@

      Either the remaining heap space or the IRQ stack has fallen below the warning limit (4000 bytes heap, 150 entries IRQ stack).

      +
        +
      • Revo : 1000 bytes heap, 150 entries IRQ stack.
      • +
      • CC/CC3D : 220 bytes heap, 100 entries IRQ stack.
      • +

          Note: if this is an original CC board (not CC3D or Revo), this condition is normal.

          - \ No newline at end of file + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/PathPlan-Warning.html b/ground/openpilotgcs/src/plugins/systemhealth/html/PathPlan-Warning.html new file mode 100644 index 000000000..37f25182e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/PathPlan-Warning.html @@ -0,0 +1,13 @@ + + + + + + + +

          Pathplanner : Warning

          +

          + No path plan has been uploaded. Not a problem if you don't intend to do autonomous missions right now. +

          + + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/Stabilization-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/Stabilization-Critical.html new file mode 100644 index 000000000..af674c0cb --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/Stabilization-Critical.html @@ -0,0 +1,17 @@ + + + + + + + +

          Stabilization : Critical

          +

          + One of the following conditions may be present: +

            +
          • Something is wrong with the Stabilization module
          • +
          • Waiting for good data from the Magnetometer or for GPS lock to perform module initialization.
          • +
          +

          + + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Stack-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/StackOverflow-Critical.html similarity index 62% rename from ground/openpilotgcs/src/plugins/systemhealth/html/fr/Stack-Critical.html rename to ground/openpilotgcs/src/plugins/systemhealth/html/StackOverflow-Critical.html index ad5e8c7ef..74c70f5c7 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Stack-Critical.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/StackOverflow-Critical.html @@ -7,7 +7,7 @@

          Stack: Critical

          - Stack overflow + Stack overflow, stack alarms are due to module memory allocation being exceeded.

          - \ No newline at end of file + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/SystemConfiguration-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/SystemConfiguration-Critical.html new file mode 100644 index 000000000..8401ea93b --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/SystemConfiguration-Critical.html @@ -0,0 +1,19 @@ + + + + + + + +

          System Configuration : Critical

          +

          + One of the following conditions may be present: +

            +
          • +

            You have set up a GPS mode (PosHold, RTB) to the flight mode switch, and you may have selected "Basic (Complementary)" fusion algorithm.

            +

            Select "GPS Navigation (INS13)" in Config -> Attitude Tab -> Parameters -> Attitude Estimation Algorithm.

            +
          • +
          +

          + + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Attitude-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Attitude-Critical.html index 04ecde767..77a583f99 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Attitude-Critical.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Attitude-Critical.html @@ -7,7 +7,11 @@

          Attitude : Critique

          - 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 : +

            +
          • Pas de données reçues en provenance des accéléromètres
          • +
          • En attente de données correctes du Magnétomètre ou d'une position GPS pour initialiser le module.
          • +

          diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Attitude-Error.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Attitude-Error.html index 60f6eb299..476756b2e 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Attitude-Error.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Attitude-Error.html @@ -7,7 +7,11 @@

          Attitude : Erreur

          - 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 : +

            +
          • Échec de l'acquisition en provenance des accéléromètres ou gyroscopes.
          • +
          • Algorithme d'évaluation de l'attitude réglé à "GPS Navigation (INS13)" et pas de magnétomètre : veuillez fixer la position Home.
          • +

          diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/CPU-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/CPUOverload-Critical.html similarity index 100% rename from ground/openpilotgcs/src/plugins/systemhealth/html/fr/CPU-Critical.html rename to ground/openpilotgcs/src/plugins/systemhealth/html/fr/CPUOverload-Critical.html diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/CPU-Warning.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/CPUOverload-Warning.html similarity index 100% rename from ground/openpilotgcs/src/plugins/systemhealth/html/fr/CPU-Warning.html rename to ground/openpilotgcs/src/plugins/systemhealth/html/fr/CPUOverload-Warning.html diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/EventSystem-Warning.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/EventSystem-Warning.html index 95e05f798..4e411c118 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/EventSystem-Warning.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/EventSystem-Warning.html @@ -5,9 +5,9 @@ -

          Event System: Warning

          +

          Event System: Avertissement

          - There were problems with UAVObject events or callbacks + Il y a des problèmes avec un événement UAVObject ou des rappels

          - \ No newline at end of file + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/GPS-Warning.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/GPS-Warning.html index 1ee18ebf1..eaa530d89 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/GPS-Warning.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/GPS-Warning.html @@ -7,7 +7,7 @@

          GPS: Avertissement

          - Le GPS a un fix et la navigation peut être utilisée. Cependant, la précision de la position est très faible (l'indication est < à 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)

          diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Magnetometer-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Magnetometer-Critical.html new file mode 100644 index 000000000..19a63867c --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Magnetometer-Critical.html @@ -0,0 +1,18 @@ + + + + + + + +

          Magnétomètre : Critique

          +

          + Des donnés proviennent du magnétomètre mais l'erreur est d'au moins 15%. Ceci peut être causé par : +

          +
            +
          • Un magnétomètre qui n'a pas été calibré.
          • +
          • Quelque chose perturbe le magnétomètre. (Fort courant)
          • +
          +

          + + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Magnetometer-Warning.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Magnetometer-Warning.html new file mode 100644 index 000000000..c879aa65b --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Magnetometer-Warning.html @@ -0,0 +1,13 @@ + + + + + + + +

          Magnétomètre : Avertissement

          +

          + Le magnétomètre a une erreur de 5% +

          + + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Memory-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Memory-Critical.html deleted file mode 100644 index 0851cd13b..000000000 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Memory-Critical.html +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - -

          Mémoire : Critique

          -

          - Either the remaining heap space or the IRQ stack has fallen below the critical limit (1000 bytes heap, 80 entries IRQ stack). -

          - - diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Memory-Warning.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Memory-Warning.html deleted file mode 100644 index 8a26b886f..000000000 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Memory-Warning.html +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - -

          Mémoire : Avertissement

          -

          - Either the remaining heap space or the IRQ stack has fallen below the warning limit (4000 bytes heap, 150 entries IRQ stack). -

          -

          - Note: if this is an original CC board (not CC3D or Revo), this condition is normal. -

          - - diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/OutOfMemory-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/OutOfMemory-Critical.html new file mode 100644 index 000000000..f8a09b12e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/OutOfMemory-Critical.html @@ -0,0 +1,17 @@ + + + + + + + +

          Mémoire : Critique

          +

          + Soit l'espace mémoire ou la pile IRQ est passé en dessous de la limite critique. +

          +
            +
          • Revo : 500 bytes heap, 80 entries IRQ stack.
          • +
          • CC/CC3D : 40 bytes heap, 60 entries IRQ stack.
          • +
              + + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/OutOfMemory-Warning.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/OutOfMemory-Warning.html new file mode 100644 index 000000000..04ba1d13f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/OutOfMemory-Warning.html @@ -0,0 +1,20 @@ + + + + + + + +

              Mémoire : Avertissement

              +

              + Soit l'espace mémoire ou la pile IRQ est passé en dessous de la limite d'avertissement. +

              +
                +
              • Revo : 1000 bytes heap, 150 entries IRQ stack.
              • +
              • CC/CC3D : 220 bytes heap, 100 entries IRQ stack.
              • +
                  +

                  + Note : si vous avez une carte CC originale (pas CC3D ou Revo), cette situation est normale. +

                  + + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/PathPlan-Warning.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/PathPlan-Warning.html new file mode 100644 index 000000000..77ec0ddca --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/PathPlan-Warning.html @@ -0,0 +1,13 @@ + + + + + + + +

                  Pathplanner : Avertissement

                  +

                  + 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. +

                  + + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Receiver-Warning.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Receiver-Warning.html index f428e2548..4bc1372c7 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Receiver-Warning.html +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Receiver-Warning.html @@ -10,7 +10,7 @@ Une des conditions suivantes semble présente :
                  • Le système est en mode failsafe.
                  • -
                  • Echec de la mise à jour d'un ou plusieurs des canaux d'accessoires.
                  • +
                  • Échec de la mise à jour d'un ou plusieurs des canaux d'accessoires.

                  diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Stabilization-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Stabilization-Critical.html new file mode 100644 index 000000000..fc7198c17 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/Stabilization-Critical.html @@ -0,0 +1,17 @@ + + + + + + + +

                  Stabilisation : Critique

                  +

                  + Une des conditions suivantes semble présente : +

                    +
                  • Quelque chose ne va pas avec le module de stabilisation
                  • +
                  • En attente de données correctes du Magnétomètre ou d'une position GPS pour initialiser le module.
                  • +
                  +

                  + + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/StackOverflow-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/StackOverflow-Critical.html new file mode 100644 index 000000000..215e42aa9 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/StackOverflow-Critical.html @@ -0,0 +1,13 @@ + + + + + + + +

                  Stack : Critique

                  +

                  + Débordement de pile : cette alarme correspond à un dépassement de la mémoire allouée sur un module. +

                  + + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/html/fr/SystemConfiguration-Critical.html b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/SystemConfiguration-Critical.html new file mode 100644 index 000000000..b4710e4dd --- /dev/null +++ b/ground/openpilotgcs/src/plugins/systemhealth/html/fr/SystemConfiguration-Critical.html @@ -0,0 +1,19 @@ + + + + + + + +

                  Configuration Système : Critique

                  +

                  + Une des conditions suivantes semble présente : +

                    +
                  • +

                    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.

                    +

                    Sélectionnez "GPS Navigation (INS13)" dans l'onglet Config -> Attitude -> Paramètres -> Algorithme d'Estimation de l'Attitude.

                    +
                  • +
                  +

                  + + diff --git a/ground/openpilotgcs/src/plugins/systemhealth/systemhealth.qrc b/ground/openpilotgcs/src/plugins/systemhealth/systemhealth.qrc index 69bb60c7e..c9f1723a0 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/systemhealth.qrc +++ b/ground/openpilotgcs/src/plugins/systemhealth/systemhealth.qrc @@ -3,8 +3,8 @@ html/Actuator-Critical.html html/Receiver-Critical.html html/Receiver-Warning.html - html/CPU-Critical.html - html/CPU-Warning.html + html/CPUOverload-Critical.html + html/CPUOverload-Warning.html html/FlightTime-Error.html html/Battery-Warning.html html/BootFault-Critical.html @@ -20,19 +20,24 @@ html/GPS-Error.html html/GPS-Warning.html html/Guidance-Warning.html - html/Memory-Critical.html - html/Memory-Warning.html + html/OutOfMemory-Critical.html + html/OutOfMemory-Warning.html html/Sensors-Critical.html html/Stabilization-Warning.html - html/Stack-Critical.html + html/StackOverflow-Critical.html html/Telemetry-Error.html + html/SystemConfiguration-Critical.html + html/PathPlan-Warning.html + html/Magnetometer-Critical.html + html/Magnetometer-Warning.html + html/Stabilization-Critical.html html/fr/Actuator-Critical.html html/fr/Receiver-Critical.html html/fr/Receiver-Warning.html - html/fr/CPU-Critical.html - html/fr/CPU-Warning.html + html/fr/CPUOverload-Critical.html + html/fr/CPUOverload-Critical.html html/fr/FlightTime-Error.html html/fr/Battery-Warning.html html/fr/BootFault-Critical.html @@ -48,12 +53,17 @@ html/fr/GPS-Error.html html/fr/GPS-Warning.html html/fr/Guidance-Warning.html - html/fr/Memory-Critical.html - html/fr/Memory-Warning.html + html/fr/OutOfMemory-Critical.html + html/fr/OutOfMemory-Warning.html html/fr/Sensors-Critical.html html/fr/Stabilization-Warning.html - html/fr/Stack-Critical.html + html/fr/StackOverflow-Critical.html html/fr/Telemetry-Error.html + html/fr/SystemConfiguration-Critical.html + html/fr/PathPlan-Warning.html + html/fr/Magnetometer-Warning.html + html/fr/Magnetometer-Critical.html + html/fr/Stabilization-Critical.html diff --git a/ground/openpilotgcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp index 572d2ae90..581b26f49 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp @@ -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()); } } diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.m.template b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.m.template index f7e683b0d..b12bea0a7 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.m.template +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.m.template @@ -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 diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index d42481a99..94225fc81 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -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 \ diff --git a/ground/openpilotgcs/src/python.pri b/ground/openpilotgcs/src/python.pri index 0ce268be5..016cfa4d3 100644 --- a/ground/openpilotgcs/src/python.pri +++ b/ground/openpilotgcs/src/python.pri @@ -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/../.. diff --git a/make/tools.mk b/make/tools.mk index 4ff9da7b9..01e63c031 100644 --- a/make/tools.mk +++ b/make/tools.mk @@ -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))) diff --git a/package/Darwin.mk b/package/Darwin.mk index 1ada9f4c2..eb6cbe373 100644 --- a/package/Darwin.mk +++ b/package/Darwin.mk @@ -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" \ ) diff --git a/package/Linux.mk b/package/Linux.mk index 66d3c284e..0acb9d2d5 100644 --- a/package/Linux.mk +++ b/package/Linux.mk @@ -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//$(VERNUM)/;s//$(SED_DATE_STRG)/ +SED_SCRIPT = s//$(DEB_VER)/;s//$(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)))) diff --git a/package/Windows.mk b/package/Windows.mk index ea474d5c5..76227d15b 100644 --- a/package/Windows.mk +++ b/package/Windows.mk @@ -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 diff --git a/package/linux/deb_amd64/control b/package/linux/deb_amd64/control deleted file mode 100644 index 4e76e63b3..000000000 --- a/package/linux/deb_amd64/control +++ /dev/null @@ -1,15 +0,0 @@ -Source: openpilot -Section: unknown -Priority: extra -Maintainer: naiiawah -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 diff --git a/package/linux/deb_common/changelog b/package/linux/deb_common/changelog deleted file mode 100644 index c6f9e1519..000000000 --- a/package/linux/deb_common/changelog +++ /dev/null @@ -1,5 +0,0 @@ -openpilot () unstable; urgency=low - - * Initial release (testing - unstable) - - -- naiiawah diff --git a/package/linux/deb_common/compat b/package/linux/deb_common/compat deleted file mode 100644 index 7f8f011eb..000000000 --- a/package/linux/deb_common/compat +++ /dev/null @@ -1 +0,0 @@ -7 diff --git a/package/linux/deb_common/docs b/package/linux/deb_common/docs deleted file mode 100644 index e69de29bb..000000000 diff --git a/package/linux/deb_common/init.d.ex b/package/linux/deb_common/init.d.ex deleted file mode 100644 index fb3e26243..000000000 --- a/package/linux/deb_common/init.d.ex +++ /dev/null @@ -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: -# Description: -# <...> -# <...> -### END INIT INFO - -# Author: naiiawah - -# 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 - -: diff --git a/package/linux/deb_common/manpage.1.ex b/package/linux/deb_common/manpage.1.ex deleted file mode 100644 index 1d0199483..000000000 --- a/package/linux/deb_common/manpage.1.ex +++ /dev/null @@ -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 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\fP and -.\" \fI\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 . -.PP -This manual page was written by naiiawah , -for the Debian project (and may be used by others). diff --git a/package/linux/deb_common/manpage.sgml.ex b/package/linux/deb_common/manpage.sgml.ex deleted file mode 100644 index 76b474e3e..000000000 --- a/package/linux/deb_common/manpage.sgml.ex +++ /dev/null @@ -1,154 +0,0 @@ - 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. - - --> - - - FIRSTNAME"> - SURNAME"> - - October 27, 2011"> - - SECTION"> - naiiawah@none"> - - OPENPILOT"> - - - Debian"> - GNU"> - GPL"> -]> - - - -
                  - &dhemail; -
                  - - &dhfirstname; - &dhsurname; - - - 2003 - &dhusername; - - &dhdate; -
                  - - &dhucpackage; - - &dhsection; - - - &dhpackage; - - program to do something - - - - &dhpackage; - - - - - - - - DESCRIPTION - - This manual page documents briefly the - &dhpackage; and bar - commands. - - 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; - Info format; see below. - - &dhpackage; is a program that... - - - - 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. - - - - - - - - Show summary of options. - - - - - - - - Show version of program. - - - - - - SEE ALSO - - bar (1), baz (1). - - The programs are documented fully by The Rise and - Fall of a Fooish Bar available via the - Info system. - - - AUTHOR - - 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. - - - On Debian systems, the complete text of the GNU General Public - License can be found in /usr/share/common-licenses/GPL. - - - -
                  - - diff --git a/package/linux/deb_common/manpage.xml.ex b/package/linux/deb_common/manpage.xml.ex deleted file mode 100644 index b8c0d8411..000000000 --- a/package/linux/deb_common/manpage.xml.ex +++ /dev/null @@ -1,291 +0,0 @@ - -.
                  will be generated. You may view the -manual page with: nroff -man .
                  | 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 - ... . - -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/ - ---> - - - - - - - - - - - - - -]> - - - - &dhtitle; - &dhpackage; - - - &dhfirstname; - &dhsurname; - Wrote this manpage for the Debian system. -
                  - &dhemail; -
                  -
                  -
                  - - 2007 - &dhusername; - - - This manual page was written 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 or (at your option) any later version published by - the Free Software Foundation. - On Debian systems, the complete text of the GNU General Public - License can be found in - /usr/share/common-licenses/GPL. - -
                  - - &dhucpackage; - &dhsection; - - - &dhpackage; - program to do something - - - - &dhpackage; - - - - - - - - - this - - - - - - - - this - that - - - - - &dhpackage; - - - - - - - - - - - - - - - - - - - DESCRIPTION - This manual page documents briefly the - &dhpackage; and bar - commands. - 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 - info - 1 - format; see below. - &dhpackage; is a program that... - - - OPTIONS - 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 - - info - 1 - files. - - - - - - - Does this and that. - - - - - - - Show summary of options. - - - - - - - Show version of program. - - - - - - FILES - - - /etc/foo.conf - - The system-wide configuration file to control the - behaviour of &dhpackage;. See - - foo.conf - 5 - for further details. - - - - ${HOME}/.foo.conf - - The per-user configuration file to control the - behaviour of &dhpackage;. See - - foo.conf - 5 - for further details. - - - - - - ENVIONMENT - - - FOO_CONF - - If used, the defined file is used as configuration - file (see also ). - - - - - - DIAGNOSTICS - The following diagnostics may be issued - on stderr: - - - Bad configuration file. Exiting. - - The configuration file seems to contain a broken configuration - line. Use the option, to get more info. - - - - - &dhpackage; provides some return codes, that can - be used in scripts: - - Code - Diagnostic - - 0 - Program exited successfully. - - - 1 - The configuration file seems to be broken. - - - - - - BUGS - The program is currently limited to only work - with the foobar library. - The upstreams BTS can be found - at . - - - SEE ALSO - - - bar - 1 - , - baz - 1 - , - foo.conf - 5 - - The programs are documented fully by The Rise and - Fall of a Fooish Bar available via the - info - 1 - system. - -
                  - diff --git a/package/linux/deb_common/menu.ex b/package/linux/deb_common/menu.ex deleted file mode 100644 index c5a80a7bc..000000000 --- a/package/linux/deb_common/menu.ex +++ /dev/null @@ -1,2 +0,0 @@ -?package(openpilot):needs="X11|text|vc|wm" section="Applications/see-menu-manual"\ - title="openpilot" command="/usr/bin/openpilot" diff --git a/package/linux/deb_common/openpilot.cron.d.ex b/package/linux/deb_common/openpilot.cron.d.ex deleted file mode 100644 index bc3507489..000000000 --- a/package/linux/deb_common/openpilot.cron.d.ex +++ /dev/null @@ -1,4 +0,0 @@ -# -# Regular cron jobs for the openpilot package -# -0 4 * * * root [ -x /usr/bin/openpilot_maintenance ] && /usr/bin/openpilot_maintenance diff --git a/package/linux/deb_common/openpilot.debhelper.log b/package/linux/deb_common/openpilot.debhelper.log deleted file mode 100644 index 34de80b19..000000000 --- a/package/linux/deb_common/openpilot.debhelper.log +++ /dev/null @@ -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 diff --git a/package/linux/deb_common/openpilot.default.ex b/package/linux/deb_common/openpilot.default.ex deleted file mode 100644 index 0b172a1fc..000000000 --- a/package/linux/deb_common/openpilot.default.ex +++ /dev/null @@ -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="" diff --git a/package/linux/deb_common/openpilot.dirs b/package/linux/deb_common/openpilot.dirs deleted file mode 100644 index 08bf6a7e1..000000000 --- a/package/linux/deb_common/openpilot.dirs +++ /dev/null @@ -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 diff --git a/package/linux/deb_common/openpilot.doc-base.EX b/package/linux/deb_common/openpilot.doc-base.EX deleted file mode 100644 index 9e24da0dc..000000000 --- a/package/linux/deb_common/openpilot.doc-base.EX +++ /dev/null @@ -1,20 +0,0 @@ -Document: openpilot -Title: Debian openpilot Manual -Author: -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 diff --git a/package/linux/deb_common/openpilot.substvars b/package/linux/deb_common/openpilot.substvars deleted file mode 100644 index 22a936a92..000000000 --- a/package/linux/deb_common/openpilot.substvars +++ /dev/null @@ -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= diff --git a/package/linux/deb_common/openpilot.udev b/package/linux/deb_common/openpilot.udev deleted file mode 100644 index fdca37665..000000000 --- a/package/linux/deb_common/openpilot.udev +++ /dev/null @@ -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" diff --git a/package/linux/deb_common/postinst.ex b/package/linux/deb_common/postinst.ex deleted file mode 100644 index e8295471c..000000000 --- a/package/linux/deb_common/postinst.ex +++ /dev/null @@ -1,39 +0,0 @@ -#!/bin/sh -# postinst script for openpilot -# -# see: dh_installdeb(1) - -set -e - -# summary of how this script can be called: -# * `configure' -# * `abort-upgrade' -# * `abort-remove' `in-favour' -# -# * `abort-remove' -# * `abort-deconfigure' `in-favour' -# `removing' -# -# 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 diff --git a/package/linux/deb_common/postrm.ex b/package/linux/deb_common/postrm.ex deleted file mode 100644 index 7494eff83..000000000 --- a/package/linux/deb_common/postrm.ex +++ /dev/null @@ -1,37 +0,0 @@ -#!/bin/sh -# postrm script for openpilot -# -# see: dh_installdeb(1) - -set -e - -# summary of how this script can be called: -# * `remove' -# * `purge' -# * `upgrade' -# * `failed-upgrade' -# * `abort-install' -# * `abort-install' -# * `abort-upgrade' -# * `disappear' -# -# for details, see http://www.debian.org/doc/debian-policy/ or -# the debian-policy package - - -case "$1" in - purge|remove|upgrade|failed-upgrade|abort-install|abort-upgrade|disappear) - ;; - - *) - echo "postrm 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 diff --git a/package/linux/deb_common/preinst.ex b/package/linux/deb_common/preinst.ex deleted file mode 100644 index 32ac40cc3..000000000 --- a/package/linux/deb_common/preinst.ex +++ /dev/null @@ -1,35 +0,0 @@ -#!/bin/sh -# preinst script for openpilot -# -# see: dh_installdeb(1) - -set -e - -# summary of how this script can be called: -# * `install' -# * `install' -# * `upgrade' -# * `abort-upgrade' -# for details, see http://www.debian.org/doc/debian-policy/ or -# the debian-policy package - - -case "$1" in - install|upgrade) - ;; - - abort-upgrade) - ;; - - *) - echo "preinst 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 diff --git a/package/linux/deb_common/prerm.ex b/package/linux/deb_common/prerm.ex deleted file mode 100644 index a46c87175..000000000 --- a/package/linux/deb_common/prerm.ex +++ /dev/null @@ -1,38 +0,0 @@ -#!/bin/sh -# prerm script for openpilot -# -# see: dh_installdeb(1) - -set -e - -# summary of how this script can be called: -# * `remove' -# * `upgrade' -# * `failed-upgrade' -# * `remove' `in-favour' -# * `deconfigure' `in-favour' -# `removing' -# -# for details, see http://www.debian.org/doc/debian-policy/ or -# the debian-policy package - - -case "$1" in - remove|upgrade|deconfigure) - ;; - - failed-upgrade) - ;; - - *) - echo "prerm 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 diff --git a/package/linux/deb_common/rules b/package/linux/deb_common/rules deleted file mode 100644 index 0977cdeed..000000000 --- a/package/linux/deb_common/rules +++ /dev/null @@ -1,85 +0,0 @@ -#!/usr/bin/make -f -# -*- makefile -*- -# Sample debian/rules that uses debhelper. -# -# This file was originally written by Joey Hess and Craig Small. -# As a special exception, when this file is copied by dh-make into a -# dh-make output file, you may use that output file without restriction. -# This special exception was added by Craig Small in version 0.37 of dh-make. -# -# Modified to make a template file for a multi-binary package with separated -# build-arch and build-indep targets by Bill Allombert 2001 - -# Uncomment this to turn on verbose mode. -# export DH_VERBOSE=1 - -# This has to be exported to make some magic below work. -export DH_OPTIONS=-v - -#%: -# dh $@ - -PACKAGE_DIR = $(shell cat build/package_dir) - -clean: - dh_testdir - dh_testroot - dh_clean - -install: - dh_testdir - dh_testroot - dh_prep - dh_installdirs - dh_installudev --priority=45 - # Add here commands to install the package into debian/ - cp -arp build/openpilotgcs_release/bin debian/openpilot/usr/local/OpenPilot - cp -arp build/openpilotgcs_release/lib debian/openpilot/usr/local/OpenPilot - cp -arp build/openpilotgcs_release/share debian/openpilot/usr/local/OpenPilot - cp -arp package/linux/qt.conf debian/openpilot/usr/local/OpenPilot/bin - cp -arp package/linux/openpilot.desktop debian/openpilot/usr/share/applications - cp -arp package/linux/openpilot.png debian/openpilot/usr/share/pixmaps - cp -arp package/linux/openpilot_menu.png debian/openpilot/usr/share/pixmaps - cp -arp package/linux/openpilot_menu.menu debian/openpilot/etc/xdg/menus/applications-merged - cp -arp package/linux/openpilot_menu.directory debian/openpilot/usr/share/desktop-directories -ifdef PACKAGE_DIR - cp -a $(PACKAGE_DIR)/*.elf debian/openpilot/usr/local/OpenPilot/firmware/ -else - $(error PACKAGE_DIR not defined! $(PACKAGE_DIR)) -endif - ln -s /usr/local/OpenPilot/bin/openpilotgcs `pwd`/debian/openpilot/usr/bin/openpilotgcs - rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/sounds/sounds - rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/pfd/pfd - rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/models/models - rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/mapicons/mapicons - rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/dials/dials - rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/diagrams/diagrams -# Removing leaked files from the dist - find debian/openpilot -name Makefile -exec rm -f {} \; - -# Build architecture-independent files here. -binary-indep: install - -# We have nothing to build by default. Got taken care of by OPs build system -# Build architecture-dependent files here. -binary-arch: install - dh_testdir - dh_testroot - dh_installchangelogs - dh_installdocs - dh_installexamples - dh_installman - dh_link - dh_strip - dh_compress - dh_fixperms - dh_installdeb - dh_shlibdeps -l/usr/local/OpenPilot/lib/openpilotgcs:/usr/local/OpenPilot/lib/qt5 --dpkg-shlibdeps-params="--ignore-missing-info -v" - dh_gencontrol - dh_md5sums - dh_builddeb -- -Zbzip2 - -binary: binary-indep binary-arch - -.PHONY: clean binary-indep binary-arch binary install - diff --git a/package/linux/deb_common/watch.ex b/package/linux/deb_common/watch.ex deleted file mode 100644 index 7e9872e99..000000000 --- a/package/linux/deb_common/watch.ex +++ /dev/null @@ -1,23 +0,0 @@ -# Example watch control file for uscan -# Rename this file to "watch" and then you can run the "uscan" command -# to check for upstream updates and more. -# See uscan(1) for format - -# Compulsory line, this is a version 3 file -version=3 - -# Uncomment to examine a Webpage -# -#http://www.example.com/downloads.php openpilot-(.*)\.tar\.gz - -# Uncomment to examine a Webserver directory -#http://www.example.com/pub/openpilot-(.*)\.tar\.gz - -# Uncommment to examine a FTP server -#ftp://ftp.example.com/pub/openpilot-(.*)\.tar\.gz debian uupdate - -# Uncomment to find new files on sourceforge, for devscripts >= 2.9 -# http://sf.net/openpilot/openpilot-(.*)\.tar\.gz - -# Uncomment to find new files on GooglePages -# http://example.googlepages.com/foo.html openpilot-(.*)\.tar\.gz diff --git a/package/linux/debian/changelog b/package/linux/debian/changelog new file mode 100644 index 000000000..9c205bb68 --- /dev/null +++ b/package/linux/debian/changelog @@ -0,0 +1,5 @@ +openpilot () unstable; urgency=low + + * Release from upstream Git (testing - unstable) + + -- James Duley diff --git a/package/linux/debian/compat b/package/linux/debian/compat new file mode 100644 index 000000000..ec635144f --- /dev/null +++ b/package/linux/debian/compat @@ -0,0 +1 @@ +9 diff --git a/package/linux/deb_i386/control b/package/linux/debian/control similarity index 68% rename from package/linux/deb_i386/control rename to package/linux/debian/control index cd59b4114..3ac0c681a 100644 --- a/package/linux/deb_i386/control +++ b/package/linux/debian/control @@ -1,15 +1,15 @@ Source: openpilot Section: unknown -Priority: extra -Maintainer: naiiawah -Build-Depends: debhelper (>= 7.0.50~) -Standards-Version: 3.8.4 +Priority: optional +Maintainer: James Duley +Build-Depends: debhelper (>= 8.0.0) +Standards-Version: 3.9.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: i386 +Architecture: any Depends: ${shlibs:Depends}, ${misc:Depends} Description: OpenPilot GCS OpenPilot Ground Control Station software diff --git a/package/linux/deb_common/copyright b/package/linux/debian/copyright similarity index 100% rename from package/linux/deb_common/copyright rename to package/linux/debian/copyright diff --git a/package/linux/debian/openpilot.udev b/package/linux/debian/openpilot.udev new file mode 120000 index 000000000..8f7360cfa --- /dev/null +++ b/package/linux/debian/openpilot.udev @@ -0,0 +1 @@ +../45-openpilot-permissions.rules \ No newline at end of file diff --git a/package/linux/deb_common/postinst b/package/linux/debian/postinst similarity index 100% rename from package/linux/deb_common/postinst rename to package/linux/debian/postinst diff --git a/package/linux/debian/rules b/package/linux/debian/rules new file mode 100644 index 000000000..7bcf5650a --- /dev/null +++ b/package/linux/debian/rules @@ -0,0 +1,25 @@ +#!/usr/bin/make -f +# -*- makefile -*- + +# Uncomment this to turn on verbose mode. +#export DH_VERBOSE=1 + +# This has to be exported to make some magic below work. +export DH_OPTIONS + + +%: + dh $@ + +# Disabled because OpenPilot makefile cleans and builds. +override_dh_auto_clean: + #$(MAKE) all_clean + +override_dh_auto_build: + #dh_auto_build -- all + +override_dh_auto_test: + # Fails non-silently because it is run under fakeroot. + +override_dh_auto_install: + dh_auto_install -- prefix=/usr diff --git a/package/linux/openpilot_menu.directory b/package/linux/openpilot_menu.directory deleted file mode 100644 index 7175a8915..000000000 --- a/package/linux/openpilot_menu.directory +++ /dev/null @@ -1,5 +0,0 @@ -[Desktop Entry] -Type=Directory -Encoding=UTF-8 -Name=OpenPilot -Icon=openpilot_menu.png diff --git a/package/linux/openpilot_menu.menu b/package/linux/openpilot_menu.menu deleted file mode 100644 index 9e35577ec..000000000 --- a/package/linux/openpilot_menu.menu +++ /dev/null @@ -1,12 +0,0 @@ - - - Applications - - OpenPilot - openpilot_menu.directory - - OpenPilotMenu - - - diff --git a/package/linux/openpilot_menu.png b/package/linux/openpilot_menu.png deleted file mode 100644 index b5e10befa..000000000 Binary files a/package/linux/openpilot_menu.png and /dev/null differ diff --git a/package/osx/package b/package/osx/package index bff3c4b6c..87cfea241 100755 --- a/package/osx/package +++ b/package/osx/package @@ -1,7 +1,7 @@ #!/bin/bash # the following environment variables must be set -: ${ROOT_DIR?} ${BUILD_DIR?} ${PACKAGE_LBL?} ${PACKAGE_DIR?} ${FW_DIR?} ${PACKAGE_NAME?} ${PACKAGE_SEP?} +: ${ROOT_DIR?} ${BUILD_DIR?} ${PACKAGE_LBL?} ${PACKAGE_DIR?} ${PACKAGE_NAME?} ${PACKAGE_SEP?} # more variables APP_PATH="${BUILD_DIR}/openpilotgcs_release/bin/OpenPilot GCS.app" @@ -39,7 +39,6 @@ fi # packaging goes here cp -a "${APP_PATH}" "/Volumes/${mountvolume}" -#ls "${FW_DIR}" | xargs -n 1 -I {} cp "${FW_DIR}/{}" "/Volumes/${VOL_NAME}/Firmware" cp "${BUILD_DIR}/uavobject-synthetics/matlab/OPLogConvert.m" "/Volumes/${mountvolume}/Utilities" cp "${ROOT_DIR}/WHATSNEW.txt" "/Volumes/${mountvolume}" cp "${ROOT_DIR}/README.txt" "/Volumes/${mountvolume}/Docs" diff --git a/package/winx86/openpilotgcs.nsi b/package/winx86/openpilotgcs.nsi index 654308576..ab8534742 100644 --- a/package/winx86/openpilotgcs.nsi +++ b/package/winx86/openpilotgcs.nsi @@ -57,7 +57,6 @@ ; !define PACKAGE_LBL "${DATE}-${TAG_OR_HASH8}" ; !define PACKAGE_DIR "..\..\build\package-$${PACKAGE_LBL}" ; !define OUT_FILE "OpenPilotGCS-$${PACKAGE_LBL}-install.exe" -; !define FIRMWARE_DIR "firmware-$${PACKAGE_LBL}" ; !define PRODUCT_VERSION "0.0.0.0" ; !define FILE_VERSION "${TAG_OR_BRANCH}:${HASH8} ${DATETIME}" ; !define BUILD_DESCRIPTION "${TAG_OR_BRANCH}:${HASH8} built from ${ORIGIN}, committed ${DATETIME} as ${HASH}" @@ -225,12 +224,6 @@ Section "-Localization" InSecLocalization File /r "${GCS_BUILD_TREE}\share\openpilotgcs\translations\qt_*.qm" SectionEnd -; Copy firmware files -Section /o "-Firmware" InSecFirmware - SetOutPath "$INSTDIR\firmware" - File /r "${PACKAGE_DIR}\${FIRMWARE_DIR}\*" -SectionEnd - ; Copy utility files Section "-Utilities" InSecUtilities SetOutPath "$INSTDIR\utilities" diff --git a/shared/uavobjectdefinition/flightstatus.xml b/shared/uavobjectdefinition/flightstatus.xml index 8d373b312..b3c92f8aa 100644 --- a/shared/uavobjectdefinition/flightstatus.xml +++ b/shared/uavobjectdefinition/flightstatus.xml @@ -5,6 +5,10 @@ + + + + diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index b6bacdd03..2fb566340 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -25,7 +25,7 @@ - + diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index be9d807ee..997ebdce0 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -16,6 +16,8 @@ elementnames="Roll,Pitch,Yaw,Collective,Accessory0,Accessory1,Accessory2"/> + + diff --git a/shared/uavobjectdefinition/pathdesired.xml b/shared/uavobjectdefinition/pathdesired.xml index a70604aa9..8296b479c 100644 --- a/shared/uavobjectdefinition/pathdesired.xml +++ b/shared/uavobjectdefinition/pathdesired.xml @@ -3,7 +3,7 @@ The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner - + @@ -12,7 +12,7 @@ FixedAttitude, SetAccessory, Land, - DisarmAlarm" default="0"/> + DisarmAlarm,Brake" default="0"/> diff --git a/shared/uavobjectdefinition/pathstatus.xml b/shared/uavobjectdefinition/pathstatus.xml index 812b7a1cf..0735d8374 100644 --- a/shared/uavobjectdefinition/pathstatus.xml +++ b/shared/uavobjectdefinition/pathstatus.xml @@ -13,6 +13,7 @@ + diff --git a/shared/uavobjectdefinition/pathsummary.xml b/shared/uavobjectdefinition/pathsummary.xml new file mode 100644 index 000000000..0f8bec9eb --- /dev/null +++ b/shared/uavobjectdefinition/pathsummary.xml @@ -0,0 +1,19 @@ + + + Summary of a completed path segment Can come from any @ref PathFollower module + + + + + + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml index a79798b4c..f0369782e 100644 --- a/shared/uavobjectdefinition/stabilizationsettings.xml +++ b/shared/uavobjectdefinition/stabilizationsettings.xml @@ -46,6 +46,10 @@ + diff --git a/shared/uavobjectdefinition/vtolpathfollowersettings.xml b/shared/uavobjectdefinition/vtolpathfollowersettings.xml index 82277f320..ec698b810 100644 --- a/shared/uavobjectdefinition/vtolpathfollowersettings.xml +++ b/shared/uavobjectdefinition/vtolpathfollowersettings.xml @@ -19,6 +19,10 @@ + + + + diff --git a/shared/uavobjectdefinition/vtolselftuningstats.xml b/shared/uavobjectdefinition/vtolselftuningstats.xml new file mode 100644 index 000000000..c36bb2cfe --- /dev/null +++ b/shared/uavobjectdefinition/vtolselftuningstats.xml @@ -0,0 +1,15 @@ + + + Automatically calculated adjustments to parameters used into vtol auto flight modes. Can come from @ref PathFollower + + + + + + + + + + + +