mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Merge branch 'next' into theothercliff/OP-1840_GPS_serial_port_needed_features
Conflicts: flight/modules/GPS/GPS.c
This commit is contained in:
commit
d9ab9e4f27
2
.gitignore
vendored
2
.gitignore
vendored
@ -2,6 +2,7 @@
|
||||
/downloads
|
||||
/tools
|
||||
/build
|
||||
/3rdparty
|
||||
|
||||
# Exclude temporary and system files
|
||||
Thumbs.db
|
||||
@ -11,6 +12,7 @@ GRTAGS
|
||||
GSYMS
|
||||
GTAGS
|
||||
core
|
||||
*~
|
||||
|
||||
# flight
|
||||
/flight/*.pnproj
|
||||
|
27
Makefile
27
Makefile
@ -113,6 +113,9 @@ endif
|
||||
# Include tools installers
|
||||
include $(ROOT_DIR)/make/tools.mk
|
||||
|
||||
# Include third party builders if available
|
||||
-include $(ROOT_DIR)/make/3rdparty/3rdparty.mk
|
||||
|
||||
# We almost need to consider autoconf/automake instead of this
|
||||
ifeq ($(UNAME), Linux)
|
||||
QT_SPEC = linux-g++
|
||||
@ -160,10 +163,10 @@ DIRS += $(UAVOBJGENERATOR_DIR)
|
||||
|
||||
.PHONY: uavobjgenerator
|
||||
uavobjgenerator: | $(UAVOBJGENERATOR_DIR)
|
||||
$(V1) ( cd $(UAVOBJGENERATOR_DIR) && \
|
||||
$(QMAKE) $(ROOT_DIR)/ground/uavobjgenerator/uavobjgenerator.pro -spec $(QT_SPEC) -r CONFIG+="$(UAVOGEN_BUILD_CONF) $(UAVOGEN_SILENT)" && \
|
||||
$(MAKE) --no-print-directory -w ; \
|
||||
)
|
||||
$(V1) cd $(UAVOBJGENERATOR_DIR) && \
|
||||
$(QMAKE) $(ROOT_DIR)/ground/uavobjgenerator/uavobjgenerator.pro \
|
||||
-spec $(QT_SPEC) -r CONFIG+=$(UAVOGEN_BUILD_CONF) CONFIG+=$(UAVOGEN_SILENT) && \
|
||||
$(MAKE) --no-print-directory -w
|
||||
|
||||
UAVOBJ_TARGETS := gcs flight python matlab java wireshark
|
||||
|
||||
@ -469,9 +472,9 @@ OPENPILOTGCS_MAKEFILE := $(OPENPILOTGCS_DIR)/Makefile
|
||||
|
||||
.PHONY: openpilotgcs_qmake
|
||||
openpilotgcs_qmake $(OPENPILOTGCS_MAKEFILE): | $(OPENPILOTGCS_DIR)
|
||||
$(V1) ( cd $(OPENPILOTGCS_DIR) && \
|
||||
$(QMAKE) $(ROOT_DIR)/ground/openpilotgcs/openpilotgcs.pro -spec $(QT_SPEC) -r CONFIG+="$(GCS_BUILD_CONF) $(GCS_SILENT)" $(GCS_QMAKE_OPTS) \
|
||||
)
|
||||
$(V1) cd $(OPENPILOTGCS_DIR) && \
|
||||
$(QMAKE) $(ROOT_DIR)/ground/openpilotgcs/openpilotgcs.pro \
|
||||
-spec $(QT_SPEC) -r CONFIG+=$(GCS_BUILD_CONF) CONFIG+=$(GCS_SILENT) $(GCS_QMAKE_OPTS)
|
||||
|
||||
.PHONY: openpilotgcs
|
||||
openpilotgcs: uavobjects_gcs $(OPENPILOTGCS_MAKEFILE)
|
||||
@ -482,6 +485,8 @@ openpilotgcs_clean:
|
||||
@$(ECHO) " CLEAN $(call toprel, $(OPENPILOTGCS_DIR))"
|
||||
$(V1) [ ! -d "$(OPENPILOTGCS_DIR)" ] || $(RM) -r "$(OPENPILOTGCS_DIR)"
|
||||
|
||||
|
||||
|
||||
################################
|
||||
#
|
||||
# Serial Uploader tool
|
||||
@ -495,9 +500,9 @@ UPLOADER_MAKEFILE := $(UPLOADER_DIR)/Makefile
|
||||
|
||||
.PHONY: uploader_qmake
|
||||
uploader_qmake $(UPLOADER_MAKEFILE): | $(UPLOADER_DIR)
|
||||
$(V1) ( cd $(UPLOADER_DIR) && \
|
||||
$(QMAKE) $(ROOT_DIR)/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/upload.pro -spec $(QT_SPEC) -r CONFIG+="$(GCS_BUILD_CONF) $(GCS_SILENT)" $(GCS_QMAKE_OPTS) \
|
||||
)
|
||||
$(V1) cd $(UPLOADER_DIR) && \
|
||||
$(QMAKE) $(ROOT_DIR)/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/upload.pro \
|
||||
-spec $(QT_SPEC) -r CONFIG+=$(GCS_BUILD_CONF) CONFIG+=$(GCS_SILENT) $(GCS_QMAKE_OPTS)
|
||||
|
||||
.PHONY: uploader
|
||||
uploader: $(UPLOADER_MAKEFILE)
|
||||
@ -711,7 +716,7 @@ $(OPFW_RESOURCE): $(FW_TARGETS) | $(OPGCSSYNTHDIR)
|
||||
|
||||
# If opfw_resource or all firmware are requested, GCS should depend on the resource
|
||||
ifneq ($(strip $(filter opfw_resource all all_fw all_flight package,$(MAKECMDGOALS))),)
|
||||
$(eval openpilotgcs_qmake: $(OPFW_RESOURCE))
|
||||
$(OPENPILOTGCS_MAKEFILE): $(OPFW_RESOURCE)
|
||||
endif
|
||||
|
||||
# Packaging targets: package
|
||||
|
14
WHATSNEW.txt
14
WHATSNEW.txt
@ -1,3 +1,17 @@
|
||||
--- RELEASE-15.02.01 ---
|
||||
This release fixes an in important bug that may prevent failsafe to work correctly using CC3D/CC with a PWM receiver.
|
||||
|
||||
The full list of bugfixes in this release is accessible here:
|
||||
https://progress.openpilot.org/issues/?filter=12260
|
||||
|
||||
|
||||
Release Notes - OpenPilot - Version RELEASE-15.02.1
|
||||
|
||||
** Bug
|
||||
* [OP-1812] - CC3D : PWM: Does not go into failsafe when RX is pulled under 50% throttle
|
||||
|
||||
|
||||
|
||||
--- RELEASE-15.02 --- Ragin' Cajun ---
|
||||
This release introduces major flight performance improvements, enhancements as well as bug fixes. Many enhancements have been made to reducing dead-time of the communication between the flight controller and ESCs. In our testing, we have found this to be not only the best flight performance so far in the OpenPilot project but the best flight performance of any project we have tested against. This is a recommended upgrade for everyone and the more skilled of a pilot you are, the more you will love this release.
|
||||
|
||||
|
@ -112,7 +112,7 @@ static inline void matrix_mult_3x3f(float a[3][3], float b[3][3], float result[3
|
||||
result[2][2] = a[0][2] * b[2][0] + a[1][2] * b[2][1] + a[2][2] * b[2][2];
|
||||
}
|
||||
|
||||
inline void matrix_inline_scale_3f(float a[3][3], float scale)
|
||||
static inline void matrix_inline_scale_3f(float a[3][3], float scale)
|
||||
{
|
||||
a[0][0] *= scale;
|
||||
a[0][1] *= scale;
|
||||
@ -127,7 +127,7 @@ inline void matrix_inline_scale_3f(float a[3][3], float scale)
|
||||
a[2][2] *= scale;
|
||||
}
|
||||
|
||||
inline void rot_about_axis_x(const float rotation, float R[3][3])
|
||||
static inline void rot_about_axis_x(const float rotation, float R[3][3])
|
||||
{
|
||||
float s = sinf(rotation);
|
||||
float c = cosf(rotation);
|
||||
@ -145,7 +145,7 @@ inline void rot_about_axis_x(const float rotation, float R[3][3])
|
||||
R[2][2] = c;
|
||||
}
|
||||
|
||||
inline void rot_about_axis_y(const float rotation, float R[3][3])
|
||||
static inline void rot_about_axis_y(const float rotation, float R[3][3])
|
||||
{
|
||||
float s = sinf(rotation);
|
||||
float c = cosf(rotation);
|
||||
@ -163,7 +163,7 @@ inline void rot_about_axis_y(const float rotation, float R[3][3])
|
||||
R[2][2] = c;
|
||||
}
|
||||
|
||||
inline void rot_about_axis_z(const float rotation, float R[3][3])
|
||||
static inline void rot_about_axis_z(const float rotation, float R[3][3])
|
||||
{
|
||||
float s = sinf(rotation);
|
||||
float c = cosf(rotation);
|
||||
|
@ -62,6 +62,7 @@ void plan_setup_returnToBase();
|
||||
* @brief setup pathplanner/pathfollower for land
|
||||
*/
|
||||
void plan_setup_land();
|
||||
void plan_setup_AutoTakeoff();
|
||||
|
||||
/**
|
||||
* @brief setup pathplanner/pathfollower for braking
|
||||
@ -90,6 +91,12 @@ void plan_setup_assistedcontrol(uint8_t timeout_occurred);
|
||||
#define PATHDESIRED_MODEPARAMETER_GOTOENDPOINT_UNUSED1 1
|
||||
#define PATHDESIRED_MODEPARAMETER_GOTOENDPOINT_UNUSED2 2
|
||||
#define PATHDESIRED_MODEPARAMETER_GOTOENDPOINT_UNUSED3 3
|
||||
|
||||
#define PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_NORTH 0
|
||||
#define PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_EAST 1
|
||||
#define PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_DOWN 2
|
||||
#define PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE 3
|
||||
|
||||
/**
|
||||
* @brief setup pathfollower for positionvario
|
||||
*/
|
||||
@ -107,6 +114,7 @@ void plan_run_PositionRoam();
|
||||
void plan_run_VelocityRoam();
|
||||
void plan_run_HomeLeash();
|
||||
void plan_run_AbsolutePosition();
|
||||
void plan_run_AutoTakeoff();
|
||||
|
||||
/**
|
||||
* @brief setup pathplanner/pathfollower for AutoCruise
|
||||
|
@ -47,7 +47,7 @@ typedef struct {
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
inline int32_t STOPWATCH_Init(uint32_t resolution, stopwatch_t *stopwatch)
|
||||
static inline int32_t STOPWATCH_Init(uint32_t resolution, stopwatch_t *stopwatch)
|
||||
{
|
||||
stopwatch->raw = PIOS_DELAY_GetRaw();
|
||||
stopwatch->resolution = resolution;
|
||||
@ -58,7 +58,7 @@ inline int32_t STOPWATCH_Init(uint32_t resolution, stopwatch_t *stopwatch)
|
||||
// ! Resets the stopwatch
|
||||
// ! \return < 0 on errors
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
inline int32_t STOPWATCH_Reset(stopwatch_t *stopwatch)
|
||||
static inline int32_t STOPWATCH_Reset(stopwatch_t *stopwatch)
|
||||
{
|
||||
stopwatch->raw = PIOS_DELAY_GetRaw();
|
||||
return 0; // no error
|
||||
@ -68,7 +68,7 @@ inline int32_t STOPWATCH_Reset(stopwatch_t *stopwatch)
|
||||
// ! Returns current value of stopwatch
|
||||
// ! \return stopwatch value
|
||||
/////////////////////////////////////////////////////////////////////////////
|
||||
inline uint32_t STOPWATCH_ValueGet(stopwatch_t *stopwatch)
|
||||
static inline uint32_t STOPWATCH_ValueGet(stopwatch_t *stopwatch)
|
||||
{
|
||||
uint32_t value = PIOS_DELAY_GetuSSince(stopwatch->raw);
|
||||
|
||||
|
@ -41,7 +41,9 @@
|
||||
#include <attitudestate.h>
|
||||
#include <vtolpathfollowersettings.h>
|
||||
#include <stabilizationbank.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <sin_lookup.h>
|
||||
#include <statusvtolautotakeoff.h>
|
||||
|
||||
#define UPDATE_EXPECTED 0.02f
|
||||
#define UPDATE_MIN 1.0e-6f
|
||||
@ -88,6 +90,7 @@ void plan_initialize()
|
||||
VelocityStateInitialize();
|
||||
VtolPathFollowerSettingsInitialize();
|
||||
StabilizationBankInitialize();
|
||||
StabilizationDesiredInitialize();
|
||||
}
|
||||
|
||||
/**
|
||||
@ -154,7 +157,7 @@ void plan_setup_returnToBase()
|
||||
pathDesired.StartingVelocity = 0.0f;
|
||||
pathDesired.EndingVelocity = 0.0f;
|
||||
|
||||
uint8_t ReturnToBaseNextCommand;
|
||||
FlightModeSettingsReturnToBaseNextCommandOptions ReturnToBaseNextCommand;
|
||||
FlightModeSettingsReturnToBaseNextCommandGet(&ReturnToBaseNextCommand);
|
||||
pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_GOTOENDPOINT_NEXTCOMMAND] = (float)ReturnToBaseNextCommand;
|
||||
pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_GOTOENDPOINT_UNUSED1] = 0.0f;
|
||||
@ -166,6 +169,155 @@ void plan_setup_returnToBase()
|
||||
}
|
||||
|
||||
|
||||
// Vtol AutoTakeoff invocation from flight mode requires the following sequence:
|
||||
// 1. Arming must be done whilst in the AutoTakeOff flight mode
|
||||
// 2. If the AutoTakeoff flight mode is selected and already armed, requires disarming first
|
||||
// 3. Wait for armed state
|
||||
// 4. Once the user increases the throttle position to above 50%, then and only then initiate auto-takeoff.
|
||||
// 5. Whilst the throttle is < 50% before takeoff, all stick inputs are being ignored.
|
||||
// 6. If during the autotakeoff sequence, at any stage, if the throttle stick position reduces to less than 10%, landing is initiated.
|
||||
|
||||
static StatusVtolAutoTakeoffControlStateOptions autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED;
|
||||
|
||||
#define AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN 2.0f
|
||||
#define AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX 50.0f
|
||||
static void plan_setup_AutoTakeoff_helper(PathDesiredData *pathDesired)
|
||||
{
|
||||
PositionStateData positionState;
|
||||
|
||||
PositionStateGet(&positionState);
|
||||
float velocity_down;
|
||||
float autotakeoff_height;
|
||||
|
||||
FlightModeSettingsAutoTakeOffVelocityGet(&velocity_down);
|
||||
FlightModeSettingsAutoTakeOffHeightGet(&autotakeoff_height);
|
||||
autotakeoff_height = fabsf(autotakeoff_height);
|
||||
if (autotakeoff_height < AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN) {
|
||||
autotakeoff_height = AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN;
|
||||
} else if (autotakeoff_height > AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX) {
|
||||
autotakeoff_height = AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX;
|
||||
}
|
||||
|
||||
|
||||
pathDesired->Start.North = positionState.North;
|
||||
pathDesired->Start.East = positionState.East;
|
||||
pathDesired->Start.Down = positionState.Down;
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_NORTH] = 0.0f;
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_EAST] = 0.0f;
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_DOWN] = -velocity_down;
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE] = (float)autotakeoffState;
|
||||
|
||||
pathDesired->End.North = positionState.North;
|
||||
pathDesired->End.East = positionState.East;
|
||||
pathDesired->End.Down = positionState.Down - autotakeoff_height;
|
||||
|
||||
pathDesired->StartingVelocity = 0.0f;
|
||||
pathDesired->EndingVelocity = 0.0f;
|
||||
pathDesired->Mode = PATHDESIRED_MODE_AUTOTAKEOFF;
|
||||
}
|
||||
|
||||
#define AUTOTAKEOFF_INFLIGHT_THROTTLE_CHECK_LIMIT 0.2f
|
||||
void plan_setup_AutoTakeoff()
|
||||
{
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED;
|
||||
// We only allow takeoff if the state transition of disarmed to armed occurs
|
||||
// whilst in the autotake flight mode
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
StabilizationDesiredData stabiDesired;
|
||||
StabilizationDesiredGet(&stabiDesired);
|
||||
|
||||
// Are we inflight?
|
||||
if (flightStatus.Armed && stabiDesired.Thrust > AUTOTAKEOFF_INFLIGHT_THROTTLE_CHECK_LIMIT) {
|
||||
// ok assume already in flight and just enter position hold
|
||||
// if we are not actually inflight this will just be a violent autotakeoff
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD;
|
||||
plan_setup_positionHold();
|
||||
} else {
|
||||
if (flightStatus.Armed) {
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_REQUIREUNARMEDFIRST;
|
||||
// Note that if this mode was invoked unintentionally whilst in flight, effectively
|
||||
// all inputs get ignored and the vtol continues to fly to its previous
|
||||
// stabi command.
|
||||
}
|
||||
PathDesiredData pathDesired;
|
||||
plan_setup_AutoTakeoff_helper(&pathDesired);
|
||||
PathDesiredSet(&pathDesired);
|
||||
}
|
||||
}
|
||||
|
||||
#define AUTOTAKEOFF_THROTTLE_LIMIT_TO_ALLOW_TAKEOFF_START 0.3f
|
||||
#define AUTOTAKEOFF_THROTTLE_ABORT_LIMIT 0.1f
|
||||
void plan_run_AutoTakeoff()
|
||||
{
|
||||
StatusVtolAutoTakeoffControlStateOptions priorState = autotakeoffState;
|
||||
|
||||
switch (autotakeoffState) {
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_REQUIREUNARMEDFIRST:
|
||||
{
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
if (!flightStatus.Armed) {
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED:
|
||||
{
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
if (flightStatus.Armed) {
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE:
|
||||
{
|
||||
ManualControlCommandData cmd;
|
||||
ManualControlCommandGet(&cmd);
|
||||
|
||||
if (cmd.Throttle > AUTOTAKEOFF_THROTTLE_LIMIT_TO_ALLOW_TAKEOFF_START) {
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_INITIATE;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_INITIATE:
|
||||
{
|
||||
ManualControlCommandData cmd;
|
||||
ManualControlCommandGet(&cmd);
|
||||
|
||||
if (cmd.Throttle < AUTOTAKEOFF_THROTTLE_ABORT_LIMIT) {
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT;
|
||||
plan_setup_land();
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT:
|
||||
{
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
if (!flightStatus.Armed) {
|
||||
autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD:
|
||||
// nothing to do. land has been requested. stay here for forever until mode change.
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if (autotakeoffState != STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT &&
|
||||
autotakeoffState != STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD) {
|
||||
if (priorState != autotakeoffState) {
|
||||
PathDesiredData pathDesired;
|
||||
plan_setup_AutoTakeoff_helper(&pathDesired);
|
||||
PathDesiredSet(&pathDesired);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void plan_setup_land_helper(PathDesiredData *pathDesired)
|
||||
{
|
||||
PositionStateData positionState;
|
||||
|
@ -74,7 +74,7 @@ int32_t configuration_check()
|
||||
// Classify navigation capability
|
||||
#ifdef REVOLUTION
|
||||
RevoSettingsInitialize();
|
||||
uint8_t revoFusion;
|
||||
RevoSettingsFusionAlgorithmOptions revoFusion;
|
||||
RevoSettingsFusionAlgorithmGet(&revoFusion);
|
||||
bool navCapableFusion;
|
||||
switch (revoFusion) {
|
||||
@ -104,8 +104,8 @@ int32_t configuration_check()
|
||||
// For each available flight mode position sanity check the available
|
||||
// modes
|
||||
uint8_t num_modes;
|
||||
uint8_t modes[FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM];
|
||||
uint8_t FlightModeAssistMap[STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NUMELEM];
|
||||
FlightModeSettingsFlightModePositionOptions modes[FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_NUMELEM];
|
||||
StabilizationSettingsFlightModeAssistMapOptions FlightModeAssistMap[STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NUMELEM];
|
||||
ManualControlSettingsFlightModeNumberGet(&num_modes);
|
||||
StabilizationSettingsFlightModeAssistMapGet(FlightModeAssistMap);
|
||||
FlightModeSettingsFlightModePositionGet(modes);
|
||||
@ -148,6 +148,7 @@ int32_t configuration_check()
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD:
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_POSITIONROAM:
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_LAND:
|
||||
case FLIGHTMODESETTINGS_FLIGHTMODEPOSITION_AUTOTAKEOFF:
|
||||
ADDSEVERITY(!coptercontrol);
|
||||
ADDSEVERITY(navCapableFusion);
|
||||
break;
|
||||
@ -208,7 +209,7 @@ int32_t configuration_check()
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t checks_disabled;
|
||||
FlightModeSettingsDisableSanityChecksOptions checks_disabled;
|
||||
FlightModeSettingsDisableSanityChecksGet(&checks_disabled);
|
||||
if (checks_disabled == FLIGHTMODESETTINGS_DISABLESANITYCHECKS_TRUE) {
|
||||
severity = SYSTEMALARMS_ALARM_WARNING;
|
||||
@ -236,22 +237,22 @@ static bool check_stabilization_settings(int index, bool multirotor, bool copter
|
||||
// Get the different axis modes for this switch position
|
||||
switch (index) {
|
||||
case 1:
|
||||
FlightModeSettingsStabilization1SettingsArrayGet(modes);
|
||||
FlightModeSettingsStabilization1SettingsArrayGet((FlightModeSettingsStabilization1SettingsOptions *)modes);
|
||||
break;
|
||||
case 2:
|
||||
FlightModeSettingsStabilization2SettingsArrayGet(modes);
|
||||
FlightModeSettingsStabilization2SettingsArrayGet((FlightModeSettingsStabilization2SettingsOptions *)modes);
|
||||
break;
|
||||
case 3:
|
||||
FlightModeSettingsStabilization3SettingsArrayGet(modes);
|
||||
FlightModeSettingsStabilization3SettingsArrayGet((FlightModeSettingsStabilization3SettingsOptions *)modes);
|
||||
break;
|
||||
case 4:
|
||||
FlightModeSettingsStabilization4SettingsArrayGet(modes);
|
||||
FlightModeSettingsStabilization4SettingsArrayGet((FlightModeSettingsStabilization4SettingsOptions *)modes);
|
||||
break;
|
||||
case 5:
|
||||
FlightModeSettingsStabilization5SettingsArrayGet(modes);
|
||||
FlightModeSettingsStabilization5SettingsArrayGet((FlightModeSettingsStabilization5SettingsOptions *)modes);
|
||||
break;
|
||||
case 6:
|
||||
FlightModeSettingsStabilization6SettingsArrayGet(modes);
|
||||
FlightModeSettingsStabilization6SettingsArrayGet((FlightModeSettingsStabilization6SettingsOptions *)modes);
|
||||
break;
|
||||
default:
|
||||
return false;
|
||||
@ -325,7 +326,7 @@ static bool check_stabilization_settings(int index, bool multirotor, bool copter
|
||||
|
||||
FrameType_t GetCurrentFrameType()
|
||||
{
|
||||
uint8_t airframe_type;
|
||||
SystemSettingsAirframeTypeOptions airframe_type;
|
||||
|
||||
SystemSettingsAirframeTypeGet(&airframe_type);
|
||||
switch ((SystemSettingsAirframeTypeOptions)airframe_type) {
|
||||
|
@ -98,7 +98,7 @@ int32_t AirspeedInitialize()
|
||||
#else
|
||||
|
||||
HwSettingsInitialize();
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
HwSettingsOptionalModulesOptions optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
HwSettingsOptionalModulesArrayGet(optionalModules);
|
||||
|
||||
|
||||
@ -110,7 +110,7 @@ int32_t AirspeedInitialize()
|
||||
}
|
||||
#endif
|
||||
|
||||
uint8_t adcRouting[HWSETTINGS_ADCROUTING_NUMELEM];
|
||||
HwSettingsADCRoutingOptions adcRouting[HWSETTINGS_ADCROUTING_NUMELEM];
|
||||
HwSettingsADCRoutingArrayGet(adcRouting);
|
||||
|
||||
// Determine if the barometric airspeed sensor is routed to an ADC pin
|
||||
@ -169,6 +169,8 @@ static void airspeedTask(__attribute__((unused)) void *parameters)
|
||||
imu_airspeedInitialize(&airspeedSettings);
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
switch (airspeedSettings.AirspeedSensorType) {
|
||||
|
@ -138,6 +138,13 @@ static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
|
||||
const float dT = SAMPLE_PERIOD_MS / 1000.0f;
|
||||
float energyRemaining;
|
||||
|
||||
// Reset ConsumedEnergy counter
|
||||
if (batterySettings.ResetConsumedEnergy) {
|
||||
flightBatteryData.ConsumedEnergy = 0;
|
||||
batterySettings.ResetConsumedEnergy = false;
|
||||
FlightBatterySettingsSet(&batterySettings);
|
||||
}
|
||||
|
||||
// calculate the battery parameters
|
||||
if (voltageADCPin >= 0) {
|
||||
flightBatteryData.Voltage = (PIOS_ADC_PinGetVolt(voltageADCPin) - batterySettings.SensorCalibrations.VoltageZero) * batterySettings.SensorCalibrations.VoltageFactor; // in Volts
|
||||
|
@ -157,6 +157,10 @@ int32_t GPSStart(void)
|
||||
int32_t GPSInitialize(void)
|
||||
{
|
||||
gpsPort = PIOS_COM_GPS;
|
||||
<<<<<<< HEAD
|
||||
=======
|
||||
GPSSettingsDataProtocolOptions gpsProtocol;
|
||||
>>>>>>> next
|
||||
|
||||
HwSettingsInitialize();
|
||||
#ifdef MODULE_GPS_BUILTIN
|
||||
@ -346,7 +350,7 @@ static void gpsTask(__attribute__((unused)) void *parameters)
|
||||
(gpsSettings.DataProtocol == GPSSETTINGS_DATAPROTOCOL_UBX && gpspositionsensor.AutoConfigStatus == GPSPOSITIONSENSOR_AUTOCONFIGSTATUS_ERROR)) {
|
||||
// we have not received any valid GPS sentences for a while.
|
||||
// either the GPS is not plugged in or a hardware problem or the GPS has locked up.
|
||||
uint8_t status = GPSPOSITIONSENSOR_STATUS_NOGPS;
|
||||
GPSPositionSensorStatusOptions status = GPSPOSITIONSENSOR_STATUS_NOGPS;
|
||||
GPSPositionSensorStatusSet(&status);
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_ERROR);
|
||||
} else {
|
||||
@ -509,72 +513,72 @@ static void updateHwSettings(UAVObjEvent __attribute__((unused)) *ev)
|
||||
// since 9600 baud and lower are not usable, and are best left at NEMA, I could have coded it to do a factory reset
|
||||
// - if set to 9600 baud (or lower)
|
||||
|
||||
if (gpsPort) {
|
||||
uint8_t speed;
|
||||
|
||||
if (gpsPort) {
|
||||
HwSettingsGPSSpeedOptions speed;
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS_UBX_PARSER) && !defined(PIOS_GPS_MINIMAL)
|
||||
// use 9600 baud during startup if autoconfig is enabled
|
||||
// that is the flag that the code should assumes a factory default baud rate
|
||||
if (ev == NULL && gpsSettings.UbxAutoConfig != GPSSETTINGS_UBXAUTOCONFIG_DISABLED) {
|
||||
speed = HWSETTINGS_GPSSPEED_9600;
|
||||
}
|
||||
else
|
||||
// use 9600 baud during startup if autoconfig is enabled
|
||||
// that is the flag that the code should assumes a factory default baud rate
|
||||
if (ev == NULL && gpsSettings.UbxAutoConfig != GPSSETTINGS_UBXAUTOCONFIG_DISABLED) {
|
||||
speed = HWSETTINGS_GPSSPEED_9600;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
// Retrieve settings
|
||||
HwSettingsGPSSpeedGet(&speed);
|
||||
}
|
||||
|
||||
// must always set the baud here, even if it looks like it is the same
|
||||
// e.g. startup sets 9600 here, ubx_autoconfig sets 57600 there, then the user selects a change back to 9600 here
|
||||
|
||||
// on startup (ev == NULL) we must set the Revo port baud rate
|
||||
// after startup (ev != NULL) we must set the Revo port baud rate only if autoconfig is disabled
|
||||
// always we must set the Revo port baud rate if not using UBX
|
||||
{
|
||||
// Retrieve settings
|
||||
HwSettingsGPSSpeedGet(&speed);
|
||||
}
|
||||
|
||||
// must always set the baud here, even if it looks like it is the same
|
||||
// e.g. startup sets 9600 here, ubx_autoconfig sets 57600 there, then the user selects a change back to 9600 here
|
||||
|
||||
// on startup (ev == NULL) we must set the Revo port baud rate
|
||||
// after startup (ev != NULL) we must set the Revo port baud rate only if autoconfig is disabled
|
||||
// always we must set the Revo port baud rate if not using UBX
|
||||
#if defined(PIOS_INCLUDE_GPS_UBX_PARSER) && !defined(PIOS_GPS_MINIMAL)
|
||||
if (ev == NULL || gpsSettings.UbxAutoConfig == GPSSETTINGS_UBXAUTOCONFIG_DISABLED || gpsSettings.DataProtocol != GPSSETTINGS_DATAPROTOCOL_UBX)
|
||||
if (ev == NULL || gpsSettings.UbxAutoConfig == GPSSETTINGS_UBXAUTOCONFIG_DISABLED || gpsSettings.DataProtocol != GPSSETTINGS_DATAPROTOCOL_UBX)
|
||||
#endif
|
||||
{
|
||||
// Set Revo port speed
|
||||
switch (speed) {
|
||||
case HWSETTINGS_GPSSPEED_2400:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 2400);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_4800:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 4800);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_9600:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 9600);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_19200:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 19200);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_38400:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 38400);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_57600:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 57600);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_115200:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 115200);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_230400:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 230400);
|
||||
break;
|
||||
}
|
||||
{
|
||||
// Set Revo port speed
|
||||
switch (speed) {
|
||||
case HWSETTINGS_GPSSPEED_2400:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 2400);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_4800:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 4800);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_9600:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 9600);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_19200:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 19200);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_38400:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 38400);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_57600:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 57600);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_115200:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 115200);
|
||||
break;
|
||||
case HWSETTINGS_GPSSPEED_230400:
|
||||
PIOS_COM_ChangeBaud(gpsPort, 230400);
|
||||
break;
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_GPS_UBX_PARSER) && !defined(PIOS_GPS_MINIMAL)
|
||||
// even changing the baud rate will make it re-verify the sensor type
|
||||
// that way the user can just try some baud rates and it when the sensor type is valid, the baud rate is correct
|
||||
ubx_reset_sensor_type();
|
||||
// even changing the baud rate will make it re-verify the sensor type
|
||||
// that way the user can just try some baud rates and it when the sensor type is valid, the baud rate is correct
|
||||
ubx_reset_sensor_type();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_GPS_UBX_PARSER) && !defined(PIOS_GPS_MINIMAL)
|
||||
else {
|
||||
// it will never do this during startup because ev == NULL
|
||||
ubx_autoconfig_set(NULL);
|
||||
}
|
||||
else {
|
||||
// it will never do this during startup because ev == NULL
|
||||
ubx_autoconfig_set(NULL);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS_UBX_PARSER) && !defined(PIOS_GPS_MINIMAL)
|
||||
|
@ -693,7 +693,7 @@ void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send)
|
||||
HwSettingsGPSSpeedGet(&hwsettings_baud);
|
||||
#if !defined(ALWAYS_RESET)
|
||||
// ALWAYS_RESET is undefined because it causes stored settings to change even with autoconfig.nostore
|
||||
// but with it off, some settings may be enabled that should really be disabled (but aren't) after autoconfig.nostore
|
||||
// but with it off, some settings may be enabled that should really be disabled (but aren't) after autoconfig.nostore
|
||||
// if user requests a low baud rate then we just reset and leave it set to NEMA
|
||||
// because low baud and high OP data rate doesn't play nice
|
||||
// if user requests that settings be saved, we will reset here too
|
||||
|
@ -134,7 +134,7 @@ static void ControlUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
}
|
||||
DebugLogEntrySet(entry);
|
||||
} else if (control.Operation == DEBUGLOGCONTROL_OPERATION_FORMATFLASH) {
|
||||
uint8_t armed;
|
||||
FlightStatusArmedOptions armed;
|
||||
FlightStatusArmedGet(&armed);
|
||||
if (armed == FLIGHTSTATUS_ARMED_DISARMED) {
|
||||
PIOS_DEBUGLOG_Format();
|
||||
|
@ -35,6 +35,9 @@
|
||||
#include <flightstatus.h>
|
||||
#include <flightmodesettings.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
#include <statusvtolland.h>
|
||||
#endif
|
||||
|
||||
// Private constants
|
||||
#define ARMED_THRESHOLD 0.50f
|
||||
@ -179,6 +182,8 @@ void armHandler(bool newinit, FrameType_t frameType)
|
||||
case FLIGHTMODESETTINGS_ARMING_ACCESSORY2:
|
||||
armingInputLevel = -1.0f * acc.AccessoryVal;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
bool manualArm = false;
|
||||
@ -313,6 +318,10 @@ static bool okToArm(void)
|
||||
case FLIGHTSTATUS_FLIGHTMODE_LAND:
|
||||
return false;
|
||||
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOTAKEOFF:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER:
|
||||
return true;
|
||||
|
||||
default:
|
||||
return false;
|
||||
|
||||
@ -336,6 +345,19 @@ static bool forcedDisArm(void)
|
||||
if (alarms.Receiver == SYSTEMALARMS_ALARM_CRITICAL) {
|
||||
return true;
|
||||
}
|
||||
|
||||
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
// check landing state if active
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
if (flightStatus.FlightMode == FLIGHTSTATUS_FLIGHTMODE_LAND) {
|
||||
StatusVtolLandData statusland;
|
||||
StatusVtolLandGet(&statusland);
|
||||
if (statusland.State == STATUSVTOLLAND_STATE_DISARMED) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -182,7 +182,7 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
frameType = GetCurrentFrameType();
|
||||
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
uint8_t TreatCustomCraftAs;
|
||||
VtolPathFollowerSettingsTreatCustomCraftAsOptions TreatCustomCraftAs;
|
||||
VtolPathFollowerSettingsTreatCustomCraftAsGet(&TreatCustomCraftAs);
|
||||
|
||||
|
||||
@ -403,6 +403,7 @@ static void manualControlTask(void)
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_POSITIONROAM:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_LAND:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOTAKEOFF:
|
||||
newFlightModeAssist = isAssistedFlightMode(position, newMode, &modeSettings);
|
||||
if (newFlightModeAssist) {
|
||||
// Set the default thrust state
|
||||
@ -485,7 +486,7 @@ static uint8_t isAssistedFlightMode(uint8_t position, uint8_t flightMode, Flight
|
||||
{
|
||||
uint8_t flightModeAssistOption = STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NONE;
|
||||
uint8_t isAssistedFlag = FLIGHTSTATUS_FLIGHTMODEASSIST_NONE;
|
||||
uint8_t FlightModeAssistMap[STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NUMELEM];
|
||||
StabilizationSettingsFlightModeAssistMapOptions FlightModeAssistMap[STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NUMELEM];
|
||||
|
||||
StabilizationSettingsFlightModeAssistMapGet(FlightModeAssistMap);
|
||||
if (position < STABILIZATIONSETTINGS_FLIGHTMODEASSISTMAP_NUMELEM) {
|
||||
@ -527,6 +528,7 @@ static uint8_t isAssistedFlightMode(uint8_t position, uint8_t flightMode, Flight
|
||||
thrustMode = FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEVARIO;
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_LAND:
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOTAKEOFF:
|
||||
thrustMode = FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_CRUISECONTROL;
|
||||
break;
|
||||
|
||||
|
@ -55,9 +55,9 @@ void pathFollowerHandler(bool newinit)
|
||||
plan_initialize();
|
||||
}
|
||||
|
||||
uint8_t flightMode;
|
||||
uint8_t assistedControlFlightMode;
|
||||
uint8_t flightModeAssist;
|
||||
FlightStatusFlightModeOptions flightMode;
|
||||
FlightStatusAssistedControlStateOptions assistedControlFlightMode;
|
||||
FlightStatusFlightModeAssistOptions flightModeAssist;
|
||||
FlightStatusFlightModeGet(&flightMode);
|
||||
FlightStatusFlightModeAssistGet(&flightModeAssist);
|
||||
FlightStatusAssistedControlStateGet(&assistedControlFlightMode);
|
||||
@ -101,6 +101,9 @@ void pathFollowerHandler(bool newinit)
|
||||
plan_setup_VelocityRoam();
|
||||
}
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOTAKEOFF:
|
||||
plan_setup_AutoTakeoff();
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOCRUISE:
|
||||
plan_setup_AutoCruise();
|
||||
break;
|
||||
@ -145,6 +148,9 @@ void pathFollowerHandler(bool newinit)
|
||||
plan_run_VelocityRoam();
|
||||
}
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOTAKEOFF:
|
||||
plan_run_AutoTakeoff();
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_AUTOCRUISE:
|
||||
plan_run_AutoCruise();
|
||||
break;
|
||||
|
@ -96,33 +96,34 @@ void stabilizedHandler(bool newinit)
|
||||
|
||||
switch (flightStatus.FlightMode) {
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1:
|
||||
stab_settings = FlightModeSettingsStabilization1SettingsToArray(settings.Stabilization1Settings);
|
||||
stab_settings = (uint8_t *)FlightModeSettingsStabilization1SettingsToArray(settings.Stabilization1Settings);
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2:
|
||||
stab_settings = FlightModeSettingsStabilization2SettingsToArray(settings.Stabilization2Settings);
|
||||
stab_settings = (uint8_t *)FlightModeSettingsStabilization2SettingsToArray(settings.Stabilization2Settings);
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3:
|
||||
stab_settings = FlightModeSettingsStabilization3SettingsToArray(settings.Stabilization3Settings);
|
||||
stab_settings = (uint8_t *)FlightModeSettingsStabilization3SettingsToArray(settings.Stabilization3Settings);
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED4:
|
||||
stab_settings = FlightModeSettingsStabilization4SettingsToArray(settings.Stabilization4Settings);
|
||||
stab_settings = (uint8_t *)FlightModeSettingsStabilization4SettingsToArray(settings.Stabilization4Settings);
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5:
|
||||
stab_settings = FlightModeSettingsStabilization5SettingsToArray(settings.Stabilization5Settings);
|
||||
stab_settings = (uint8_t *)FlightModeSettingsStabilization5SettingsToArray(settings.Stabilization5Settings);
|
||||
break;
|
||||
case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6:
|
||||
stab_settings = FlightModeSettingsStabilization6SettingsToArray(settings.Stabilization6Settings);
|
||||
stab_settings = (uint8_t *)FlightModeSettingsStabilization6SettingsToArray(settings.Stabilization6Settings);
|
||||
break;
|
||||
default:
|
||||
// Major error, this should not occur because only enter this block when one of these is true
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
stab_settings = FlightModeSettingsStabilization1SettingsToArray(settings.Stabilization1Settings);
|
||||
stab_settings = (uint8_t *)FlightModeSettingsStabilization1SettingsToArray(settings.Stabilization1Settings);
|
||||
return;
|
||||
}
|
||||
|
||||
stabilization.Roll =
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) ? cmd.Roll :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd.Roll * stabSettings.ManualRate.Roll :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATETRAINER) ? cmd.Roll * stabSettings.ManualRate.Roll :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd.Roll * stabSettings.RollMax :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd.Roll * stabSettings.RollMax :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd.Roll * stabSettings.ManualRate.Roll :
|
||||
@ -134,6 +135,7 @@ void stabilizedHandler(bool newinit)
|
||||
stabilization.Pitch =
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) ? cmd.Pitch :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd.Pitch * stabSettings.ManualRate.Pitch :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATETRAINER) ? cmd.Pitch * stabSettings.ManualRate.Pitch :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd.Pitch * stabSettings.PitchMax :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd.Pitch * stabSettings.PitchMax :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd.Pitch * stabSettings.ManualRate.Pitch :
|
||||
@ -155,6 +157,7 @@ void stabilizedHandler(bool newinit)
|
||||
stabilization.Yaw =
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL) ? cmd.Yaw :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd.Yaw * stabSettings.ManualRate.Yaw :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATETRAINER) ? cmd.Yaw * stabSettings.ManualRate.Yaw :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd.Yaw * stabSettings.YawMax :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd.Yaw * stabSettings.YawMax :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd.Yaw * stabSettings.ManualRate.Yaw :
|
||||
|
@ -42,8 +42,8 @@ void takeOffLocationHandlerInit()
|
||||
{
|
||||
TakeOffLocationInitialize();
|
||||
// check whether there is a preset/valid takeoff location
|
||||
uint8_t mode;
|
||||
uint8_t status;
|
||||
TakeOffLocationModeOptions mode;
|
||||
TakeOffLocationStatusOptions status;
|
||||
TakeOffLocationModeGet(&mode);
|
||||
TakeOffLocationStatusGet(&status);
|
||||
// preset with invalid location will actually behave like FirstTakeoff
|
||||
@ -61,8 +61,8 @@ void takeOffLocationHandlerInit()
|
||||
*/
|
||||
void takeOffLocationHandler()
|
||||
{
|
||||
uint8_t armed;
|
||||
uint8_t status;
|
||||
FlightStatusArmedOptions armed;
|
||||
TakeOffLocationStatusOptions status;
|
||||
|
||||
FlightStatusArmedGet(&armed);
|
||||
|
||||
@ -77,7 +77,7 @@ void takeOffLocationHandler()
|
||||
case FLIGHTSTATUS_ARMED_ARMING:
|
||||
case FLIGHTSTATUS_ARMED_ARMED:
|
||||
if (!locationSet || status != TAKEOFFLOCATION_STATUS_VALID) {
|
||||
uint8_t mode;
|
||||
TakeOffLocationModeOptions mode;
|
||||
TakeOffLocationModeGet(&mode);
|
||||
|
||||
if ((mode != TAKEOFFLOCATION_MODE_PRESET) || (status == TAKEOFFLOCATION_STATUS_INVALID)) {
|
||||
@ -91,7 +91,7 @@ void takeOffLocationHandler()
|
||||
case FLIGHTSTATUS_ARMED_DISARMED:
|
||||
// unset if location is to be acquired at each arming
|
||||
if (locationSet) {
|
||||
uint8_t mode;
|
||||
TakeOffLocationModeOptions mode;
|
||||
TakeOffLocationModeGet(&mode);
|
||||
if (mode == TAKEOFFLOCATION_MODE_ARMINGLOCATION) {
|
||||
locationSet = false;
|
||||
|
76
flight/modules/PathFollower/inc/vtolautotakeoffcontroller.h
Normal file
76
flight/modules/PathFollower/inc/vtolautotakeoffcontroller.h
Normal file
@ -0,0 +1,76 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup PathFollower CONTROL interface class
|
||||
* @brief vtol land controller class
|
||||
* @{
|
||||
*
|
||||
* @file vtollandcontroller.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015.
|
||||
* @brief Executes CONTROL for landing sequence
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef VTOLAUTOTAKEOFFCONTROLLER_H
|
||||
#define VTOLAUTOTAKEOFFCONTROLLER_H
|
||||
#include "pathfollowercontrol.h"
|
||||
#include "pidcontroldown.h"
|
||||
#include "pidcontrolne.h"
|
||||
// forward decl
|
||||
class VtolAutoTakeoffFSM;
|
||||
class VtolAutoTakeoffController : public PathFollowerControl {
|
||||
private:
|
||||
static VtolAutoTakeoffController *p_inst;
|
||||
VtolAutoTakeoffController();
|
||||
|
||||
|
||||
public:
|
||||
static VtolAutoTakeoffController *instance()
|
||||
{
|
||||
if (!p_inst) {
|
||||
p_inst = new VtolAutoTakeoffController();
|
||||
}
|
||||
return p_inst;
|
||||
}
|
||||
|
||||
int32_t Initialize(VtolPathFollowerSettingsData *vtolPathFollowerSettings);
|
||||
|
||||
|
||||
void Activate(void);
|
||||
void Deactivate(void);
|
||||
void SettingsUpdated(void);
|
||||
void UpdateAutoPilot(void);
|
||||
void ObjectiveUpdated(void);
|
||||
uint8_t IsActive(void);
|
||||
uint8_t Mode(void);
|
||||
|
||||
private:
|
||||
void UpdateVelocityDesired(void);
|
||||
int8_t UpdateStabilizationDesired(bool yaw_attitude, float yaw_direction);
|
||||
void setArmedIfChanged(FlightStatusArmedOptions val);
|
||||
|
||||
VtolAutoTakeoffFSM *fsm;
|
||||
VtolPathFollowerSettingsData *vtolPathFollowerSettings;
|
||||
PIDControlDown controlDown;
|
||||
PIDControlNE controlNE;
|
||||
uint8_t mActive;
|
||||
};
|
||||
|
||||
#endif // VTOLAUTOTAKEOFFCONTROLLER_H
|
158
flight/modules/PathFollower/inc/vtolautotakeofffsm.h
Normal file
158
flight/modules/PathFollower/inc/vtolautotakeofffsm.h
Normal file
@ -0,0 +1,158 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup PathFollower FSM
|
||||
* @brief Executes landing sequence via an FSM
|
||||
* @{
|
||||
*
|
||||
* @file vtollandfsm.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015.
|
||||
* @brief Executes FSM for landing sequence
|
||||
*
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef VTOLAUTOTAKEOFFFSM_H
|
||||
#define VTOLAUTOTAKEOFFFSM_H
|
||||
|
||||
extern "C" {
|
||||
#include "statusvtolautotakeoff.h"
|
||||
}
|
||||
#include "pathfollowerfsm.h"
|
||||
|
||||
// AutoTakeoffing state machine
|
||||
typedef enum {
|
||||
AUTOTAKEOFF_STATE_INACTIVE = 0, // Inactive state is the initialised state on startup
|
||||
AUTOTAKEOFF_STATE_CHECKSTATE, // Initial condition checks
|
||||
AUTOTAKEOFF_STATE_SLOWSTART, // Slow start motors
|
||||
AUTOTAKEOFF_STATE_THRUSTUP, // Ramp motors up to neutral thrust
|
||||
AUTOTAKEOFF_STATE_TAKEOFF, // Ascend to target velocity
|
||||
AUTOTAKEOFF_STATE_HOLD, // Hold position as completion of the sequence
|
||||
AUTOTAKEOFF_STATE_THRUSTDOWN, // Thrust down sequence
|
||||
AUTOTAKEOFF_STATE_THRUSTOFF, // Thrust is now off
|
||||
AUTOTAKEOFF_STATE_DISARMED, // Disarmed
|
||||
AUTOTAKEOFF_STATE_ABORT, // Abort on error triggerig fallback to hold
|
||||
AUTOTAKEOFF_STATE_SIZE
|
||||
} PathFollowerFSM_AutoTakeoffState_T;
|
||||
|
||||
class VtolAutoTakeoffFSM : public PathFollowerFSM {
|
||||
private:
|
||||
static VtolAutoTakeoffFSM *p_inst;
|
||||
VtolAutoTakeoffFSM();
|
||||
|
||||
public:
|
||||
static VtolAutoTakeoffFSM *instance()
|
||||
{
|
||||
if (!p_inst) {
|
||||
p_inst = new VtolAutoTakeoffFSM();
|
||||
}
|
||||
return p_inst;
|
||||
}
|
||||
int32_t Initialize(VtolPathFollowerSettingsData *vtolPathFollowerSettings,
|
||||
PathDesiredData *pathDesired,
|
||||
FlightStatusData *flightStatus);
|
||||
void Inactive(void);
|
||||
void Activate(void);
|
||||
void Update(void);
|
||||
void BoundThrust(float &ulow, float &uhigh);
|
||||
PathFollowerFSMState_T GetCurrentState(void);
|
||||
void ConstrainStabiDesired(StabilizationDesiredData *stabDesired);
|
||||
void Abort(void);
|
||||
uint8_t PositionHoldState(void);
|
||||
void setControlState(StatusVtolAutoTakeoffControlStateOptions controlState);
|
||||
|
||||
protected:
|
||||
|
||||
// FSM instance data type
|
||||
typedef struct {
|
||||
StatusVtolAutoTakeoffData fsmAutoTakeoffStatus;
|
||||
StatusVtolAutoTakeoffStateOptions currentState;
|
||||
TakeOffLocationData takeOffLocation;
|
||||
uint32_t stateRunCount;
|
||||
uint32_t stateTimeoutCount;
|
||||
float sum1;
|
||||
float sum2;
|
||||
float expectedAutoTakeoffPositionNorth;
|
||||
float expectedAutoTakeoffPositionEast;
|
||||
float thrustLimit;
|
||||
float boundThrustMin;
|
||||
float boundThrustMax;
|
||||
uint8_t observationCount;
|
||||
uint8_t observation2Count;
|
||||
uint8_t flZeroStabiHorizontal;
|
||||
uint8_t flConstrainThrust;
|
||||
uint8_t flLowAltitude;
|
||||
uint8_t flAltitudeHold;
|
||||
} VtolAutoTakeoffFSMData_T;
|
||||
|
||||
// FSM state structure
|
||||
typedef struct {
|
||||
void(VtolAutoTakeoffFSM::*setup) (void); // Called to initialise the state
|
||||
void(VtolAutoTakeoffFSM::*run) (uint8_t); // Run the event detection code for a state
|
||||
} PathFollowerFSM_AutoTakeoffStateHandler_T;
|
||||
|
||||
// Private variables
|
||||
VtolAutoTakeoffFSMData_T *mAutoTakeoffData;
|
||||
VtolPathFollowerSettingsData *vtolPathFollowerSettings;
|
||||
PathDesiredData *pathDesired;
|
||||
FlightStatusData *flightStatus;
|
||||
|
||||
void setup_inactive(void);
|
||||
|
||||
void setup_checkstate(void);
|
||||
|
||||
void setup_slowstart(void);
|
||||
void run_slowstart(uint8_t);
|
||||
|
||||
void setup_takeoff(void);
|
||||
void run_takeoff(uint8_t);
|
||||
|
||||
void setup_hold(void);
|
||||
void run_hold(uint8_t);
|
||||
|
||||
void setup_thrustup(void);
|
||||
void run_thrustup(uint8_t);
|
||||
|
||||
void setup_thrustdown(void);
|
||||
void run_thrustdown(uint8_t);
|
||||
|
||||
void setup_thrustoff(void);
|
||||
void run_thrustoff(uint8_t);
|
||||
|
||||
void setup_disarmed(void);
|
||||
void run_disarmed(uint8_t);
|
||||
|
||||
void setup_abort(void);
|
||||
void run_abort(uint8_t);
|
||||
|
||||
void initFSM(void);
|
||||
void setState(StatusVtolAutoTakeoffStateOptions newState, StatusVtolAutoTakeoffStateExitReasonOptions reason);
|
||||
int32_t runState();
|
||||
int32_t runAlways();
|
||||
|
||||
void updateVtolAutoTakeoffFSMStatus();
|
||||
void assessAltitude(void);
|
||||
|
||||
void setStateTimeout(int32_t count);
|
||||
void fallback_to_hold(void);
|
||||
|
||||
static PathFollowerFSM_AutoTakeoffStateHandler_T sAutoTakeoffStateTable[AUTOTAKEOFF_STATE_SIZE];
|
||||
};
|
||||
|
||||
#endif // VTOLAUTOTAKEOFFFSM_H
|
@ -64,7 +64,7 @@ public:
|
||||
private:
|
||||
void UpdateVelocityDesired(void);
|
||||
int8_t UpdateStabilizationDesired(bool yaw_attitude, float yaw_direction);
|
||||
void setArmedIfChanged(uint8_t val);
|
||||
void setArmedIfChanged(FlightStatusArmedOptions val);
|
||||
|
||||
PathFollowerFSM *fsm;
|
||||
VtolPathFollowerSettingsData *vtolPathFollowerSettings;
|
||||
|
@ -82,7 +82,7 @@ protected:
|
||||
// FSM instance data type
|
||||
typedef struct {
|
||||
StatusVtolLandData fsmLandStatus;
|
||||
PathFollowerFSM_LandState_T currentState;
|
||||
StatusVtolLandStateOptions currentState;
|
||||
TakeOffLocationData takeOffLocation;
|
||||
uint32_t stateRunCount;
|
||||
uint32_t stateTimeoutCount;
|
||||
@ -133,7 +133,7 @@ protected:
|
||||
void setup_abort(void);
|
||||
void run_abort(uint8_t);
|
||||
void initFSM(void);
|
||||
void setState(PathFollowerFSM_LandState_T newState, StatusVtolLandStateExitReasonOptions reason);
|
||||
void setState(StatusVtolLandStateOptions newState, StatusVtolLandStateExitReasonOptions reason);
|
||||
int32_t runState();
|
||||
int32_t runAlways();
|
||||
void updateVtolLandFSMStatus();
|
||||
|
@ -81,12 +81,14 @@ extern "C" {
|
||||
#include <pidstatus.h>
|
||||
#include <homelocation.h>
|
||||
#include <accelstate.h>
|
||||
#include <statusvtolautotakeoff.h>
|
||||
#include <statusvtolland.h>
|
||||
#include <statusgrounddrive.h>
|
||||
}
|
||||
|
||||
#include "pathfollowercontrol.h"
|
||||
#include "vtollandcontroller.h"
|
||||
#include "vtolautotakeoffcontroller.h"
|
||||
#include "vtolvelocitycontroller.h"
|
||||
#include "vtolbrakecontroller.h"
|
||||
#include "vtolflycontroller.h"
|
||||
@ -172,6 +174,7 @@ extern "C" int32_t PathFollowerInitialize()
|
||||
PIDStatusInitialize();
|
||||
StatusVtolLandInitialize();
|
||||
StatusGroundDriveInitialize();
|
||||
StatusVtolAutoTakeoffInitialize();
|
||||
|
||||
// VtolLandFSM additional objects
|
||||
HomeLocationInitialize();
|
||||
@ -206,6 +209,7 @@ void pathFollowerInitializeControllersForFrameType()
|
||||
case FRAME_TYPE_HELI:
|
||||
if (!multirotor_initialised) {
|
||||
VtolLandController::instance()->Initialize(&vtolPathFollowerSettings);
|
||||
VtolAutoTakeoffController::instance()->Initialize(&vtolPathFollowerSettings);
|
||||
VtolVelocityController::instance()->Initialize(&vtolPathFollowerSettings);
|
||||
VtolFlyController::instance()->Initialize(&vtolPathFollowerSettings);
|
||||
VtolBrakeController::instance()->Initialize(&vtolPathFollowerSettings);
|
||||
@ -263,6 +267,10 @@ static void pathFollowerSetActiveController(void)
|
||||
activeController = VtolLandController::instance();
|
||||
activeController->Activate();
|
||||
break;
|
||||
case PATHDESIRED_MODE_AUTOTAKEOFF:
|
||||
activeController = VtolAutoTakeoffController::instance();
|
||||
activeController->Activate();
|
||||
break;
|
||||
default:
|
||||
activeController = 0;
|
||||
break;
|
||||
|
@ -89,8 +89,7 @@ void PIDControlDown::Activate()
|
||||
float currentThrust;
|
||||
|
||||
StabilizationDesiredThrustGet(¤tThrust);
|
||||
float u0 = currentThrust - mNeutral;
|
||||
pid2_transfer(&PID, u0);
|
||||
pid2_transfer(&PID, currentThrust);
|
||||
mActive = true;
|
||||
}
|
||||
|
||||
|
@ -61,11 +61,6 @@ void PIDControlNE::Deactivate()
|
||||
|
||||
void PIDControlNE::Activate()
|
||||
{
|
||||
// Do we need to initialise any loops for smooth transition
|
||||
// float currentNE;
|
||||
// StabilizationDesiredNEGet(¤tNE);
|
||||
// float u0 = currentNE - mNeutral;
|
||||
// pid2_transfer(&PID, u0);
|
||||
mActive = true;
|
||||
}
|
||||
|
||||
|
287
flight/modules/PathFollower/vtolautotakeoffcontroller.cpp
Normal file
287
flight/modules/PathFollower/vtolautotakeoffcontroller.cpp
Normal file
@ -0,0 +1,287 @@
|
||||
/*
|
||||
******************************************************************************
|
||||
*
|
||||
* @file vtollandcontroller.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015.
|
||||
* @brief Vtol landing controller loop
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
extern "C" {
|
||||
#include <openpilot.h>
|
||||
|
||||
#include <callbackinfo.h>
|
||||
|
||||
#include <math.h>
|
||||
#include <pid.h>
|
||||
#include <CoordinateConversions.h>
|
||||
#include <sin_lookup.h>
|
||||
#include <pathdesired.h>
|
||||
#include <paths.h>
|
||||
#include "plans.h"
|
||||
#include <sanitycheck.h>
|
||||
|
||||
#include <homelocation.h>
|
||||
#include <accelstate.h>
|
||||
#include <vtolpathfollowersettings.h>
|
||||
#include <flightstatus.h>
|
||||
#include <flightmodesettings.h>
|
||||
#include <pathstatus.h>
|
||||
#include <positionstate.h>
|
||||
#include <velocitystate.h>
|
||||
#include <velocitydesired.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <airspeedstate.h>
|
||||
#include <attitudestate.h>
|
||||
#include <takeofflocation.h>
|
||||
#include <poilocation.h>
|
||||
#include <manualcontrolcommand.h>
|
||||
#include <systemsettings.h>
|
||||
#include <stabilizationbank.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <vtolselftuningstats.h>
|
||||
#include <pathsummary.h>
|
||||
}
|
||||
|
||||
// C++ includes
|
||||
#include "vtolautotakeoffcontroller.h"
|
||||
#include "pathfollowerfsm.h"
|
||||
#include "vtolautotakeofffsm.h"
|
||||
#include "pidcontroldown.h"
|
||||
|
||||
// Private constants
|
||||
|
||||
// pointer to a singleton instance
|
||||
VtolAutoTakeoffController *VtolAutoTakeoffController::p_inst = 0;
|
||||
|
||||
VtolAutoTakeoffController::VtolAutoTakeoffController()
|
||||
: fsm(0), vtolPathFollowerSettings(0), mActive(false)
|
||||
{}
|
||||
|
||||
// Called when mode first engaged
|
||||
void VtolAutoTakeoffController::Activate(void)
|
||||
{
|
||||
if (!mActive) {
|
||||
mActive = true;
|
||||
SettingsUpdated();
|
||||
fsm->Activate();
|
||||
controlDown.Activate();
|
||||
controlNE.Activate();
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t VtolAutoTakeoffController::IsActive(void)
|
||||
{
|
||||
return mActive;
|
||||
}
|
||||
|
||||
uint8_t VtolAutoTakeoffController::Mode(void)
|
||||
{
|
||||
return PATHDESIRED_MODE_AUTOTAKEOFF;
|
||||
}
|
||||
|
||||
// Objective updated in pathdesired, e.g. same flight mode but new target velocity
|
||||
void VtolAutoTakeoffController::ObjectiveUpdated(void)
|
||||
{
|
||||
// Set the objective's target velocity
|
||||
|
||||
controlDown.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_DOWN]);
|
||||
controlNE.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_NORTH],
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_EAST]);
|
||||
controlNE.UpdatePositionSetpoint(pathDesired->End.North, pathDesired->End.East);
|
||||
controlDown.UpdatePositionSetpoint(pathDesired->End.Down);
|
||||
fsm->setControlState((StatusVtolAutoTakeoffControlStateOptions)pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE]);
|
||||
}
|
||||
void VtolAutoTakeoffController::Deactivate(void)
|
||||
{
|
||||
if (mActive) {
|
||||
mActive = false;
|
||||
fsm->Inactive();
|
||||
controlDown.Deactivate();
|
||||
controlNE.Deactivate();
|
||||
}
|
||||
}
|
||||
|
||||
// AutoTakeoff Uses different vertical velocity PID.
|
||||
void VtolAutoTakeoffController::SettingsUpdated(void)
|
||||
{
|
||||
const float dT = vtolPathFollowerSettings->UpdatePeriod / 1000.0f;
|
||||
|
||||
controlNE.UpdateParameters(vtolPathFollowerSettings->HorizontalVelPID.Kp,
|
||||
vtolPathFollowerSettings->HorizontalVelPID.Ki,
|
||||
vtolPathFollowerSettings->HorizontalVelPID.Kd,
|
||||
vtolPathFollowerSettings->HorizontalVelPID.ILimit,
|
||||
dT,
|
||||
vtolPathFollowerSettings->HorizontalVelMax);
|
||||
|
||||
|
||||
controlNE.UpdatePositionalParameters(vtolPathFollowerSettings->HorizontalPosP);
|
||||
controlNE.UpdateCommandParameters(-vtolPathFollowerSettings->MaxRollPitch, vtolPathFollowerSettings->MaxRollPitch, vtolPathFollowerSettings->VelocityFeedforward);
|
||||
|
||||
controlDown.UpdateParameters(vtolPathFollowerSettings->AutoTakeoffVerticalVelPID.Kp,
|
||||
vtolPathFollowerSettings->AutoTakeoffVerticalVelPID.Ki,
|
||||
vtolPathFollowerSettings->AutoTakeoffVerticalVelPID.Kd,
|
||||
vtolPathFollowerSettings->AutoTakeoffVerticalVelPID.Beta,
|
||||
dT,
|
||||
vtolPathFollowerSettings->VerticalVelMax);
|
||||
controlDown.UpdatePositionalParameters(vtolPathFollowerSettings->VerticalPosP);
|
||||
VtolSelfTuningStatsData vtolSelfTuningStats;
|
||||
VtolSelfTuningStatsGet(&vtolSelfTuningStats);
|
||||
controlDown.UpdateNeutralThrust(vtolSelfTuningStats.NeutralThrustOffset + vtolPathFollowerSettings->ThrustLimits.Neutral);
|
||||
controlDown.SetThrustLimits(vtolPathFollowerSettings->ThrustLimits.Min, vtolPathFollowerSettings->ThrustLimits.Max);
|
||||
fsm->SettingsUpdated();
|
||||
}
|
||||
|
||||
// AutoTakeoff Uses a different FSM to its parent
|
||||
int32_t VtolAutoTakeoffController::Initialize(VtolPathFollowerSettingsData *ptr_vtolPathFollowerSettings)
|
||||
{
|
||||
PIOS_Assert(ptr_vtolPathFollowerSettings);
|
||||
vtolPathFollowerSettings = ptr_vtolPathFollowerSettings;
|
||||
|
||||
if (fsm == 0) {
|
||||
fsm = VtolAutoTakeoffFSM::instance();
|
||||
VtolAutoTakeoffFSM::instance()->Initialize(vtolPathFollowerSettings, pathDesired, flightStatus);
|
||||
controlDown.Initialize(fsm);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
void VtolAutoTakeoffController::UpdateVelocityDesired()
|
||||
{
|
||||
VelocityStateData velocityState;
|
||||
|
||||
VelocityStateGet(&velocityState);
|
||||
VelocityDesiredData velocityDesired;
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
|
||||
if (fsm->PositionHoldState()) {
|
||||
controlDown.UpdatePositionState(positionState.Down);
|
||||
controlDown.ControlPosition();
|
||||
}
|
||||
|
||||
controlDown.UpdateVelocityState(velocityState.Down);
|
||||
controlNE.UpdateVelocityState(velocityState.North, velocityState.East);
|
||||
|
||||
controlNE.UpdatePositionState(positionState.North, positionState.East);
|
||||
controlNE.ControlPosition();
|
||||
|
||||
velocityDesired.Down = controlDown.GetVelocityDesired();
|
||||
float north, east;
|
||||
controlNE.GetVelocityDesired(&north, &east);
|
||||
velocityDesired.North = north;
|
||||
velocityDesired.East = east;
|
||||
|
||||
// update pathstatus
|
||||
pathStatus->error = 0.0f;
|
||||
pathStatus->fractional_progress = 0.0f;
|
||||
if (fsm->PositionHoldState()) {
|
||||
pathStatus->fractional_progress = 1.0f;
|
||||
// note if the takeoff waypoint and the launch position are significantly different
|
||||
// the above check might need to expand to assessment of north and east.
|
||||
}
|
||||
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;
|
||||
|
||||
VelocityDesiredSet(&velocityDesired);
|
||||
}
|
||||
|
||||
int8_t VtolAutoTakeoffController::UpdateStabilizationDesired(bool yaw_attitude, float yaw_direction)
|
||||
{
|
||||
uint8_t result = 1;
|
||||
StabilizationDesiredData stabDesired;
|
||||
AttitudeStateData attitudeState;
|
||||
StabilizationBankData stabSettings;
|
||||
float northCommand;
|
||||
float eastCommand;
|
||||
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
AttitudeStateGet(&attitudeState);
|
||||
StabilizationBankGet(&stabSettings);
|
||||
|
||||
controlNE.GetNECommand(&northCommand, &eastCommand);
|
||||
stabDesired.Thrust = controlDown.GetDownCommand();
|
||||
|
||||
float angle_radians = DEG2RAD(attitudeState.Yaw);
|
||||
float cos_angle = cosf(angle_radians);
|
||||
float sine_angle = sinf(angle_radians);
|
||||
float maxPitch = vtolPathFollowerSettings->MaxRollPitch;
|
||||
stabDesired.StabilizationMode.Pitch = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
|
||||
stabDesired.Pitch = boundf(-northCommand * cos_angle - eastCommand * sine_angle, -maxPitch, maxPitch);
|
||||
stabDesired.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
|
||||
stabDesired.Roll = boundf(-northCommand * sine_angle + eastCommand * cos_angle, -maxPitch, maxPitch);
|
||||
|
||||
ManualControlCommandData manualControl;
|
||||
ManualControlCommandGet(&manualControl);
|
||||
|
||||
if (yaw_attitude) {
|
||||
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
|
||||
stabDesired.Yaw = yaw_direction;
|
||||
} else {
|
||||
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK;
|
||||
stabDesired.Yaw = stabSettings.MaximumRate.Yaw * manualControl.Yaw;
|
||||
}
|
||||
|
||||
// default thrust mode to cruise control
|
||||
stabDesired.StabilizationMode.Thrust = STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL;
|
||||
|
||||
fsm->ConstrainStabiDesired(&stabDesired); // excludes thrust
|
||||
StabilizationDesiredSet(&stabDesired);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffController::UpdateAutoPilot()
|
||||
{
|
||||
fsm->Update();
|
||||
|
||||
UpdateVelocityDesired();
|
||||
|
||||
// yaw behaviour is configurable in vtolpathfollower, select yaw control algorithm
|
||||
bool yaw_attitude = true;
|
||||
float yaw = 0.0f;
|
||||
|
||||
fsm->GetYaw(yaw_attitude, yaw);
|
||||
|
||||
int8_t result = UpdateStabilizationDesired(yaw_attitude, yaw);
|
||||
|
||||
if (!result) {
|
||||
fsm->Abort();
|
||||
}
|
||||
|
||||
if (fsm->GetCurrentState() == PFFSM_STATE_DISARMED) {
|
||||
setArmedIfChanged(FLIGHTSTATUS_ARMED_DISARMED);
|
||||
}
|
||||
|
||||
PathStatusSet(pathStatus);
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffController::setArmedIfChanged(FlightStatusArmedOptions val)
|
||||
{
|
||||
if (flightStatus->Armed != val) {
|
||||
flightStatus->Armed = val;
|
||||
FlightStatusSet(flightStatus);
|
||||
}
|
||||
}
|
590
flight/modules/PathFollower/vtolautotakeofffsm.cpp
Normal file
590
flight/modules/PathFollower/vtolautotakeofffsm.cpp
Normal file
@ -0,0 +1,590 @@
|
||||
/*
|
||||
******************************************************************************
|
||||
*
|
||||
* @file vtolautotakeofffsm.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015.
|
||||
* @brief This autotakeoff state machine is a helper state machine to the
|
||||
* VtolAutoTakeoffController.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
extern "C" {
|
||||
#include <openpilot.h>
|
||||
|
||||
#include <callbackinfo.h>
|
||||
|
||||
#include <math.h>
|
||||
#include <pid.h>
|
||||
#include <pathdesired.h>
|
||||
#include <paths.h>
|
||||
#include "plans.h"
|
||||
#include <sanitycheck.h>
|
||||
|
||||
#include <homelocation.h>
|
||||
#include <accelstate.h>
|
||||
#include <vtolpathfollowersettings.h>
|
||||
#include <flightstatus.h>
|
||||
#include <flightmodesettings.h>
|
||||
#include <pathstatus.h>
|
||||
#include <positionstate.h>
|
||||
#include <velocitystate.h>
|
||||
#include <velocitydesired.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <attitudestate.h>
|
||||
#include <takeofflocation.h>
|
||||
#include <manualcontrolcommand.h>
|
||||
#include <systemsettings.h>
|
||||
#include <stabilizationbank.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <vtolselftuningstats.h>
|
||||
#include <statusvtolautotakeoff.h>
|
||||
#include <pathsummary.h>
|
||||
}
|
||||
|
||||
// C++ includes
|
||||
#include <vtolautotakeofffsm.h>
|
||||
|
||||
|
||||
// Private constants
|
||||
#define TIMER_COUNT_PER_SECOND (1000 / vtolPathFollowerSettings->UpdatePeriod)
|
||||
#define TIMEOUT_SLOWSTART (2 * TIMER_COUNT_PER_SECOND)
|
||||
#define TIMEOUT_THRUSTUP (1 * TIMER_COUNT_PER_SECOND)
|
||||
#define TIMEOUT_THRUSTDOWN (2 * TIMER_COUNT_PER_SECOND)
|
||||
#define AUTOTAKEOFFING_SLOWDOWN_HEIGHT -5.0f
|
||||
|
||||
VtolAutoTakeoffFSM::PathFollowerFSM_AutoTakeoffStateHandler_T VtolAutoTakeoffFSM::sAutoTakeoffStateTable[AUTOTAKEOFF_STATE_SIZE] = {
|
||||
[AUTOTAKEOFF_STATE_INACTIVE] = { .setup = &VtolAutoTakeoffFSM::setup_inactive, .run = 0 },
|
||||
[AUTOTAKEOFF_STATE_CHECKSTATE] = { .setup = &VtolAutoTakeoffFSM::setup_checkstate, .run = 0 },
|
||||
[AUTOTAKEOFF_STATE_SLOWSTART] = { .setup = &VtolAutoTakeoffFSM::setup_slowstart, .run = &VtolAutoTakeoffFSM::run_slowstart },
|
||||
[AUTOTAKEOFF_STATE_THRUSTUP] = { .setup = &VtolAutoTakeoffFSM::setup_thrustup, .run = &VtolAutoTakeoffFSM::run_thrustup },
|
||||
[AUTOTAKEOFF_STATE_TAKEOFF] = { .setup = &VtolAutoTakeoffFSM::setup_takeoff, .run = &VtolAutoTakeoffFSM::run_takeoff },
|
||||
[AUTOTAKEOFF_STATE_HOLD] = { .setup = &VtolAutoTakeoffFSM::setup_hold, .run = &VtolAutoTakeoffFSM::run_hold },
|
||||
[AUTOTAKEOFF_STATE_THRUSTDOWN] = { .setup = &VtolAutoTakeoffFSM::setup_thrustdown, .run = &VtolAutoTakeoffFSM::run_thrustdown },
|
||||
[AUTOTAKEOFF_STATE_THRUSTOFF] = { .setup = &VtolAutoTakeoffFSM::setup_thrustoff, .run = &VtolAutoTakeoffFSM::run_thrustoff },
|
||||
[AUTOTAKEOFF_STATE_DISARMED] = { .setup = &VtolAutoTakeoffFSM::setup_disarmed, .run = &VtolAutoTakeoffFSM::run_disarmed },
|
||||
[AUTOTAKEOFF_STATE_ABORT] = { .setup = &VtolAutoTakeoffFSM::setup_abort, .run = &VtolAutoTakeoffFSM::run_abort }
|
||||
};
|
||||
|
||||
// pointer to a singleton instance
|
||||
VtolAutoTakeoffFSM *VtolAutoTakeoffFSM::p_inst = 0;
|
||||
|
||||
|
||||
VtolAutoTakeoffFSM::VtolAutoTakeoffFSM()
|
||||
: mAutoTakeoffData(0), vtolPathFollowerSettings(0), pathDesired(0), flightStatus(0)
|
||||
{}
|
||||
|
||||
// Private types
|
||||
|
||||
// Private functions
|
||||
// Public API methods
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t VtolAutoTakeoffFSM::Initialize(VtolPathFollowerSettingsData *ptr_vtolPathFollowerSettings,
|
||||
PathDesiredData *ptr_pathDesired,
|
||||
FlightStatusData *ptr_flightStatus)
|
||||
{
|
||||
PIOS_Assert(ptr_vtolPathFollowerSettings);
|
||||
PIOS_Assert(ptr_pathDesired);
|
||||
PIOS_Assert(ptr_flightStatus);
|
||||
|
||||
if (mAutoTakeoffData == 0) {
|
||||
mAutoTakeoffData = (VtolAutoTakeoffFSMData_T *)pios_malloc(sizeof(VtolAutoTakeoffFSMData_T));
|
||||
PIOS_Assert(mAutoTakeoffData);
|
||||
}
|
||||
memset(mAutoTakeoffData, 0, sizeof(VtolAutoTakeoffFSMData_T));
|
||||
vtolPathFollowerSettings = ptr_vtolPathFollowerSettings;
|
||||
pathDesired = ptr_pathDesired;
|
||||
flightStatus = ptr_flightStatus;
|
||||
initFSM();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::Inactive(void)
|
||||
{
|
||||
memset(mAutoTakeoffData, 0, sizeof(VtolAutoTakeoffFSMData_T));
|
||||
initFSM();
|
||||
}
|
||||
|
||||
// Initialise the FSM
|
||||
void VtolAutoTakeoffFSM::initFSM(void)
|
||||
{
|
||||
if (vtolPathFollowerSettings != 0) {
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_INACTIVE, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
} else {
|
||||
mAutoTakeoffData->currentState = STATUSVTOLAUTOTAKEOFF_STATE_INACTIVE;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::Activate()
|
||||
{
|
||||
memset(mAutoTakeoffData, 0, sizeof(VtolAutoTakeoffFSMData_T));
|
||||
mAutoTakeoffData->currentState = STATUSVTOLAUTOTAKEOFF_STATE_INACTIVE;
|
||||
mAutoTakeoffData->flLowAltitude = true;
|
||||
mAutoTakeoffData->flAltitudeHold = false;
|
||||
mAutoTakeoffData->boundThrustMin = 0.0f;
|
||||
mAutoTakeoffData->boundThrustMax = 0.0f;
|
||||
mAutoTakeoffData->flZeroStabiHorizontal = true; // turn off positional controllers
|
||||
TakeOffLocationGet(&(mAutoTakeoffData->takeOffLocation));
|
||||
mAutoTakeoffData->fsmAutoTakeoffStatus.AltitudeAtState[STATUSVTOLAUTOTAKEOFF_STATE_INACTIVE] = 0.0f;
|
||||
mAutoTakeoffData->fsmAutoTakeoffStatus.ControlState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED;
|
||||
assessAltitude();
|
||||
|
||||
// Check if we are already flying. This can happen in pathplanner mode
|
||||
// going into a second loop of the waypoints.
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
if (stabDesired.Thrust > vtolPathFollowerSettings->ThrustLimits.Min) {
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_HOLD, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
return;
|
||||
}
|
||||
|
||||
// initially inactive and wait for a change in controlstate.
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_INACTIVE, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::Abort(void)
|
||||
{
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_ABORT, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
}
|
||||
|
||||
PathFollowerFSMState_T VtolAutoTakeoffFSM::GetCurrentState(void)
|
||||
{
|
||||
switch (mAutoTakeoffData->currentState) {
|
||||
case STATUSVTOLAUTOTAKEOFF_STATE_INACTIVE:
|
||||
return PFFSM_STATE_INACTIVE;
|
||||
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_STATE_ABORT:
|
||||
return PFFSM_STATE_ABORT;
|
||||
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_STATE_DISARMED:
|
||||
return PFFSM_STATE_DISARMED;
|
||||
|
||||
break;
|
||||
default:
|
||||
return PFFSM_STATE_ACTIVE;
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::Update()
|
||||
{
|
||||
runState();
|
||||
if (GetCurrentState() != PFFSM_STATE_INACTIVE) {
|
||||
runAlways();
|
||||
}
|
||||
}
|
||||
|
||||
int32_t VtolAutoTakeoffFSM::runState(void)
|
||||
{
|
||||
uint8_t flTimeout = false;
|
||||
|
||||
mAutoTakeoffData->stateRunCount++;
|
||||
|
||||
if (mAutoTakeoffData->stateTimeoutCount > 0 && mAutoTakeoffData->stateRunCount > mAutoTakeoffData->stateTimeoutCount) {
|
||||
flTimeout = true;
|
||||
}
|
||||
|
||||
// If the current state has a static function, call it
|
||||
if (sAutoTakeoffStateTable[mAutoTakeoffData->currentState].run) {
|
||||
(this->*sAutoTakeoffStateTable[mAutoTakeoffData->currentState].run)(flTimeout);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t VtolAutoTakeoffFSM::runAlways(void)
|
||||
{
|
||||
void assessAltitude(void);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
// PathFollower implements the PID scheme and has a objective
|
||||
// set by a PathDesired object. Based on the mode, pathfollower
|
||||
// uses FSM's as helper functions that manage state and event detection.
|
||||
// PathFollower calls into FSM methods to alter its commands.
|
||||
|
||||
void VtolAutoTakeoffFSM::BoundThrust(float &ulow, float &uhigh)
|
||||
{
|
||||
ulow = mAutoTakeoffData->boundThrustMin;
|
||||
uhigh = mAutoTakeoffData->boundThrustMax;
|
||||
|
||||
|
||||
if (mAutoTakeoffData->flConstrainThrust) {
|
||||
uhigh = mAutoTakeoffData->thrustLimit;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::ConstrainStabiDesired(StabilizationDesiredData *stabDesired)
|
||||
{
|
||||
if (mAutoTakeoffData->flZeroStabiHorizontal && stabDesired) {
|
||||
stabDesired->Pitch = 0.0f;
|
||||
stabDesired->Roll = 0.0f;
|
||||
stabDesired->Yaw = 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
// Set the new state and perform setup for subsequent state run calls
|
||||
// This is called by state run functions on event detection that drive
|
||||
// state transitions.
|
||||
void VtolAutoTakeoffFSM::setState(StatusVtolAutoTakeoffStateOptions newState, StatusVtolAutoTakeoffStateExitReasonOptions reason)
|
||||
{
|
||||
mAutoTakeoffData->fsmAutoTakeoffStatus.StateExitReason[mAutoTakeoffData->currentState] = reason;
|
||||
|
||||
if (mAutoTakeoffData->currentState == newState) {
|
||||
return;
|
||||
}
|
||||
mAutoTakeoffData->currentState = newState;
|
||||
|
||||
if (newState != STATUSVTOLAUTOTAKEOFF_STATE_INACTIVE) {
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
float takeOffDown = 0.0f;
|
||||
if (mAutoTakeoffData->takeOffLocation.Status == TAKEOFFLOCATION_STATUS_VALID) {
|
||||
takeOffDown = mAutoTakeoffData->takeOffLocation.Down;
|
||||
}
|
||||
mAutoTakeoffData->fsmAutoTakeoffStatus.AltitudeAtState[newState] = positionState.Down - takeOffDown;
|
||||
assessAltitude();
|
||||
}
|
||||
|
||||
// Restart state timer counter
|
||||
mAutoTakeoffData->stateRunCount = 0;
|
||||
|
||||
// Reset state timeout to disabled/zero
|
||||
mAutoTakeoffData->stateTimeoutCount = 0;
|
||||
|
||||
if (sAutoTakeoffStateTable[mAutoTakeoffData->currentState].setup) {
|
||||
(this->*sAutoTakeoffStateTable[mAutoTakeoffData->currentState].setup)();
|
||||
}
|
||||
|
||||
updateVtolAutoTakeoffFSMStatus();
|
||||
}
|
||||
|
||||
|
||||
// Timeout utility function for use by state init implementations
|
||||
void VtolAutoTakeoffFSM::setStateTimeout(int32_t count)
|
||||
{
|
||||
mAutoTakeoffData->stateTimeoutCount = count;
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::updateVtolAutoTakeoffFSMStatus()
|
||||
{
|
||||
mAutoTakeoffData->fsmAutoTakeoffStatus.State = mAutoTakeoffData->currentState;
|
||||
if (mAutoTakeoffData->flLowAltitude) {
|
||||
mAutoTakeoffData->fsmAutoTakeoffStatus.AltitudeState = STATUSVTOLAUTOTAKEOFF_ALTITUDESTATE_LOW;
|
||||
} else {
|
||||
mAutoTakeoffData->fsmAutoTakeoffStatus.AltitudeState = STATUSVTOLAUTOTAKEOFF_ALTITUDESTATE_HIGH;
|
||||
}
|
||||
StatusVtolAutoTakeoffSet(&mAutoTakeoffData->fsmAutoTakeoffStatus);
|
||||
}
|
||||
|
||||
|
||||
void VtolAutoTakeoffFSM::assessAltitude(void)
|
||||
{
|
||||
float positionDown;
|
||||
|
||||
PositionStateDownGet(&positionDown);
|
||||
float takeOffDown = 0.0f;
|
||||
if (mAutoTakeoffData->takeOffLocation.Status == TAKEOFFLOCATION_STATUS_VALID) {
|
||||
takeOffDown = mAutoTakeoffData->takeOffLocation.Down;
|
||||
}
|
||||
float positionDownRelativeToTakeoff = positionDown - takeOffDown;
|
||||
if (positionDownRelativeToTakeoff < AUTOTAKEOFFING_SLOWDOWN_HEIGHT) {
|
||||
mAutoTakeoffData->flLowAltitude = false;
|
||||
} else {
|
||||
mAutoTakeoffData->flLowAltitude = true;
|
||||
}
|
||||
}
|
||||
|
||||
// Action the required state from plans.c
|
||||
void VtolAutoTakeoffFSM::setControlState(StatusVtolAutoTakeoffControlStateOptions controlState)
|
||||
{
|
||||
mAutoTakeoffData->fsmAutoTakeoffStatus.ControlState = controlState;
|
||||
|
||||
switch (controlState) {
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED:
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_INACTIVE, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE:
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_INACTIVE, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_REQUIREUNARMEDFIRST:
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_INACTIVE, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_INITIATE:
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_CHECKSTATE, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD:
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_HOLD, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
break;
|
||||
case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT:
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_ABORT, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// State: INACTIVE
|
||||
void VtolAutoTakeoffFSM::setup_inactive(void)
|
||||
{
|
||||
// Re-initialise local variables
|
||||
mAutoTakeoffData->flZeroStabiHorizontal = false;
|
||||
mAutoTakeoffData->flConstrainThrust = false;
|
||||
}
|
||||
|
||||
// State: CHECKSTATE
|
||||
void VtolAutoTakeoffFSM::setup_checkstate(void)
|
||||
{
|
||||
// Assumptions that do not need to be checked if flight mode is AUTOTAKEOFF
|
||||
// 1. Already armed
|
||||
// 2. Not in flight. This was checked in plans.c
|
||||
// 3. User has placed throttle position to more than 50% to allow autotakeoff
|
||||
|
||||
// If pathplanner, we need additional checks
|
||||
// E.g. if inflight, this mode is just positon hol
|
||||
StabilizationDesiredData stabDesired;
|
||||
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
if (stabDesired.Thrust > vtolPathFollowerSettings->ThrustLimits.Min) {
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_HOLD, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
// Start from a enforced thrust off condition
|
||||
mAutoTakeoffData->flConstrainThrust = false;
|
||||
mAutoTakeoffData->boundThrustMin = -0.1f;
|
||||
mAutoTakeoffData->boundThrustMax = 0.0f;
|
||||
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_SLOWSTART, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
|
||||
// STATE: SLOWSTART spools up motors to vtol min over 2 seconds for effect.
|
||||
// PID loops may be cumulating I terms but that problem needs to be solved
|
||||
#define SLOWSTART_INITIAL_THRUST 0.05f // assumed to be less than vtol min
|
||||
void VtolAutoTakeoffFSM::setup_slowstart(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_SLOWSTART);
|
||||
mAutoTakeoffData->flZeroStabiHorizontal = true; // turn off positional controllers
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
float vtol_thrust_min = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
if (vtol_thrust_min < SLOWSTART_INITIAL_THRUST) {
|
||||
vtol_thrust_min = SLOWSTART_INITIAL_THRUST;
|
||||
}
|
||||
mAutoTakeoffData->sum1 = (vtol_thrust_min - SLOWSTART_INITIAL_THRUST) / (float)TIMEOUT_SLOWSTART;
|
||||
mAutoTakeoffData->sum2 = vtol_thrust_min;
|
||||
mAutoTakeoffData->boundThrustMin = SLOWSTART_INITIAL_THRUST;
|
||||
mAutoTakeoffData->boundThrustMax = SLOWSTART_INITIAL_THRUST;
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
mAutoTakeoffData->expectedAutoTakeoffPositionNorth = positionState.North;
|
||||
mAutoTakeoffData->expectedAutoTakeoffPositionEast = positionState.East;
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::run_slowstart(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
// increase thrust setpoint step by step
|
||||
if (mAutoTakeoffData->boundThrustMin < mAutoTakeoffData->sum2) {
|
||||
mAutoTakeoffData->boundThrustMin += mAutoTakeoffData->sum1;
|
||||
}
|
||||
mAutoTakeoffData->boundThrustMax += mAutoTakeoffData->sum1;
|
||||
if (mAutoTakeoffData->boundThrustMax > mAutoTakeoffData->sum2) {
|
||||
mAutoTakeoffData->boundThrustMax = mAutoTakeoffData->sum2;
|
||||
}
|
||||
|
||||
if (flTimeout) {
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_THRUSTUP, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
// STATE: THRUSTUP spools up motors to vtol min over 5 seconds for effect.
|
||||
// PID loops may be cumulating I terms but that problem needs to be solved
|
||||
#define THRUSTUP_FINAL_THRUST_AS_RATIO_OF_VTOLMAX 0.8f
|
||||
void VtolAutoTakeoffFSM::setup_thrustup(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_THRUSTUP);
|
||||
mAutoTakeoffData->flZeroStabiHorizontal = false;
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
mAutoTakeoffData->sum2 = THRUSTUP_FINAL_THRUST_AS_RATIO_OF_VTOLMAX * vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
mAutoTakeoffData->sum1 = (mAutoTakeoffData->sum2 - mAutoTakeoffData->boundThrustMax) / (float)TIMEOUT_THRUSTUP;
|
||||
mAutoTakeoffData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::run_thrustup(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
// increase thrust setpoint step by step
|
||||
mAutoTakeoffData->boundThrustMax += mAutoTakeoffData->sum1;
|
||||
if (mAutoTakeoffData->boundThrustMax > mAutoTakeoffData->sum2) {
|
||||
mAutoTakeoffData->boundThrustMax = mAutoTakeoffData->sum2;
|
||||
}
|
||||
|
||||
if (flTimeout) {
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_TAKEOFF, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// STATE: TAKEOFF
|
||||
void VtolAutoTakeoffFSM::setup_takeoff(void)
|
||||
{
|
||||
mAutoTakeoffData->flZeroStabiHorizontal = false;
|
||||
}
|
||||
void VtolAutoTakeoffFSM::run_takeoff(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
StabilizationDesiredData stabDesired;
|
||||
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
if (stabDesired.Thrust < 0.0f) {
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_THRUSTOFF, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_ZEROTHRUST);
|
||||
return;
|
||||
}
|
||||
|
||||
// detect broad sideways drift.
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
float north_error = mAutoTakeoffData->expectedAutoTakeoffPositionNorth - positionState.North;
|
||||
float east_error = mAutoTakeoffData->expectedAutoTakeoffPositionEast - positionState.East;
|
||||
float down_error = pathDesired->End.Down - positionState.Down;
|
||||
float positionError = sqrtf(north_error * north_error + east_error * east_error);
|
||||
if (positionError > 3.0f) {
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_THRUSTDOWN, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_POSITIONERROR);
|
||||
return;
|
||||
}
|
||||
if (fabsf(down_error) < 0.5f) {
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_HOLD, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_ARRIVEDATALT);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// STATE: HOLD
|
||||
void VtolAutoTakeoffFSM::setup_hold(void)
|
||||
{
|
||||
mAutoTakeoffData->flZeroStabiHorizontal = false;
|
||||
mAutoTakeoffData->flAltitudeHold = true;
|
||||
}
|
||||
void VtolAutoTakeoffFSM::run_hold(__attribute__((unused)) uint8_t flTimeout)
|
||||
{}
|
||||
|
||||
uint8_t VtolAutoTakeoffFSM::PositionHoldState(void)
|
||||
{
|
||||
return mAutoTakeoffData->flAltitudeHold;
|
||||
}
|
||||
|
||||
// STATE: THRUSTDOWN
|
||||
void VtolAutoTakeoffFSM::setup_thrustdown(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_THRUSTDOWN);
|
||||
mAutoTakeoffData->flZeroStabiHorizontal = true;
|
||||
mAutoTakeoffData->flConstrainThrust = true;
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
mAutoTakeoffData->thrustLimit = stabDesired.Thrust;
|
||||
mAutoTakeoffData->sum1 = stabDesired.Thrust / (float)TIMEOUT_THRUSTDOWN;
|
||||
mAutoTakeoffData->boundThrustMin = -0.1f;
|
||||
mAutoTakeoffData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Neutral;
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::run_thrustdown(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
// reduce thrust setpoint step by step
|
||||
mAutoTakeoffData->thrustLimit -= mAutoTakeoffData->sum1;
|
||||
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
if (stabDesired.Thrust < 0.0f || mAutoTakeoffData->thrustLimit < 0.0f) {
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_THRUSTOFF, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_ZEROTHRUST);
|
||||
}
|
||||
|
||||
if (flTimeout) {
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_THRUSTOFF, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
// STATE: THRUSTOFF
|
||||
void VtolAutoTakeoffFSM::setup_thrustoff(void)
|
||||
{
|
||||
mAutoTakeoffData->thrustLimit = -1.0f;
|
||||
mAutoTakeoffData->flConstrainThrust = true;
|
||||
mAutoTakeoffData->boundThrustMin = -0.1f;
|
||||
mAutoTakeoffData->boundThrustMax = 0.0f;
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::run_thrustoff(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
setState(STATUSVTOLAUTOTAKEOFF_STATE_DISARMED, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
}
|
||||
|
||||
// STATE: DISARMED
|
||||
void VtolAutoTakeoffFSM::setup_disarmed(void)
|
||||
{
|
||||
// nothing to do
|
||||
mAutoTakeoffData->flConstrainThrust = false;
|
||||
mAutoTakeoffData->flZeroStabiHorizontal = false;
|
||||
mAutoTakeoffData->observationCount = 0;
|
||||
mAutoTakeoffData->boundThrustMin = -0.1f;
|
||||
mAutoTakeoffData->boundThrustMax = 0.0f;
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::run_disarmed(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
#ifdef DEBUG_GROUNDIMPACT
|
||||
if (mAutoTakeoffData->observationCount++ > 100) {
|
||||
setState(AUTOTAKEOFF_STATE_WTG_FOR_GROUNDEFFECT, STATUSVTOLAUTOTAKEOFF_STATEEXITREASON_NONE);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::fallback_to_hold(void)
|
||||
{
|
||||
PositionStateData positionState;
|
||||
|
||||
PositionStateGet(&positionState);
|
||||
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_GOTOENDPOINT;
|
||||
|
||||
PathDesiredSet(pathDesired);
|
||||
}
|
||||
|
||||
// abort repeatedly overwrites pathfollower's objective on a landing abort and
|
||||
// continues to do so until a flight mode change.
|
||||
void VtolAutoTakeoffFSM::setup_abort(void)
|
||||
{
|
||||
mAutoTakeoffData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mAutoTakeoffData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
mAutoTakeoffData->flConstrainThrust = false;
|
||||
mAutoTakeoffData->flZeroStabiHorizontal = false;
|
||||
fallback_to_hold();
|
||||
}
|
||||
|
||||
void VtolAutoTakeoffFSM::run_abort(__attribute__((unused)) uint8_t flTimeout)
|
||||
{}
|
@ -312,8 +312,10 @@ int8_t VtolBrakeController::UpdateStabilizationDesired(void)
|
||||
// and a better throttle management to the standard Position Hold.
|
||||
thrustMode = FLIGHTMODESETTINGS_STABILIZATION1SETTINGS_ALTITUDEVARIO;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
stabDesired.StabilizationMode.Thrust = thrustMode;
|
||||
stabDesired.StabilizationMode.Thrust = (StabilizationDesiredStabilizationModeOptions)thrustMode;
|
||||
}
|
||||
|
||||
// set the thrust value
|
||||
|
@ -101,7 +101,7 @@ int32_t VtolBrakeFSM::Initialize(VtolPathFollowerSettingsData *ptr_vtolPathFollo
|
||||
mBrakeData = (VtolBrakeFSMData_T *)pios_malloc(sizeof(VtolBrakeFSMData_T));
|
||||
PIOS_Assert(mBrakeData);
|
||||
}
|
||||
memset(mBrakeData, sizeof(VtolBrakeFSMData_T), 0);
|
||||
memset(mBrakeData, 0, sizeof(VtolBrakeFSMData_T));
|
||||
vtolPathFollowerSettings = ptr_vtolPathFollowerSettings;
|
||||
pathDesired = ptr_pathDesired;
|
||||
flightStatus = ptr_flightStatus;
|
||||
@ -113,7 +113,7 @@ int32_t VtolBrakeFSM::Initialize(VtolPathFollowerSettingsData *ptr_vtolPathFollo
|
||||
|
||||
void VtolBrakeFSM::Inactive(void)
|
||||
{
|
||||
memset(mBrakeData, sizeof(VtolBrakeFSMData_T), 0);
|
||||
memset(mBrakeData, 0, sizeof(VtolBrakeFSMData_T));
|
||||
initFSM();
|
||||
}
|
||||
|
||||
@ -125,7 +125,7 @@ void VtolBrakeFSM::initFSM(void)
|
||||
|
||||
void VtolBrakeFSM::Activate()
|
||||
{
|
||||
memset(mBrakeData, sizeof(VtolBrakeFSMData_T), 0);
|
||||
memset(mBrakeData, 0, sizeof(VtolBrakeFSMData_T));
|
||||
mBrakeData->currentState = BRAKE_STATE_INACTIVE;
|
||||
setState(BRAKE_STATE_BRAKE, FSMBRAKESTATUS_STATEEXITREASON_NONE);
|
||||
}
|
||||
|
@ -1,283 +1,275 @@
|
||||
/*
|
||||
******************************************************************************
|
||||
*
|
||||
* @file vtollandcontroller.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015.
|
||||
* @brief Vtol landing controller loop
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
extern "C" {
|
||||
#include <openpilot.h>
|
||||
|
||||
#include <callbackinfo.h>
|
||||
|
||||
#include <math.h>
|
||||
#include <pid.h>
|
||||
#include <CoordinateConversions.h>
|
||||
#include <sin_lookup.h>
|
||||
#include <pathdesired.h>
|
||||
#include <paths.h>
|
||||
#include "plans.h"
|
||||
#include <sanitycheck.h>
|
||||
|
||||
#include <accelstate.h>
|
||||
#include <vtolpathfollowersettings.h>
|
||||
#include <flightstatus.h>
|
||||
#include <flightmodesettings.h>
|
||||
#include <pathstatus.h>
|
||||
#include <positionstate.h>
|
||||
#include <velocitystate.h>
|
||||
#include <velocitydesired.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <attitudestate.h>
|
||||
#include <takeofflocation.h>
|
||||
#include <manualcontrolcommand.h>
|
||||
#include <systemsettings.h>
|
||||
#include <stabilizationbank.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <vtolselftuningstats.h>
|
||||
#include <pathsummary.h>
|
||||
}
|
||||
|
||||
// C++ includes
|
||||
#include "vtollandcontroller.h"
|
||||
#include "pathfollowerfsm.h"
|
||||
#include "vtollandfsm.h"
|
||||
#include "pidcontroldown.h"
|
||||
|
||||
// Private constants
|
||||
|
||||
// pointer to a singleton instance
|
||||
VtolLandController *VtolLandController::p_inst = 0;
|
||||
|
||||
VtolLandController::VtolLandController()
|
||||
: fsm(NULL), vtolPathFollowerSettings(NULL), mActive(false)
|
||||
{}
|
||||
|
||||
// Called when mode first engaged
|
||||
void VtolLandController::Activate(void)
|
||||
{
|
||||
if (!mActive) {
|
||||
mActive = true;
|
||||
SettingsUpdated();
|
||||
fsm->Activate();
|
||||
controlDown.Activate();
|
||||
controlNE.Activate();
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t VtolLandController::IsActive(void)
|
||||
{
|
||||
return mActive;
|
||||
}
|
||||
|
||||
uint8_t VtolLandController::Mode(void)
|
||||
{
|
||||
return PATHDESIRED_MODE_LAND;
|
||||
}
|
||||
|
||||
// Objective updated in pathdesired, e.g. same flight mode but new target velocity
|
||||
void VtolLandController::ObjectiveUpdated(void)
|
||||
{
|
||||
// Set the objective's target velocity
|
||||
controlDown.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_DOWN]);
|
||||
controlNE.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_NORTH],
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_EAST]);
|
||||
controlNE.UpdatePositionSetpoint(pathDesired->End.North, pathDesired->End.East);
|
||||
}
|
||||
void VtolLandController::Deactivate(void)
|
||||
{
|
||||
if (mActive) {
|
||||
mActive = false;
|
||||
fsm->Inactive();
|
||||
controlDown.Deactivate();
|
||||
controlNE.Deactivate();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void VtolLandController::SettingsUpdated(void)
|
||||
{
|
||||
const float dT = vtolPathFollowerSettings->UpdatePeriod / 1000.0f;
|
||||
|
||||
controlNE.UpdateParameters(vtolPathFollowerSettings->HorizontalVelPID.Kp,
|
||||
vtolPathFollowerSettings->HorizontalVelPID.Ki,
|
||||
vtolPathFollowerSettings->HorizontalVelPID.Kd,
|
||||
vtolPathFollowerSettings->HorizontalVelPID.ILimit,
|
||||
dT,
|
||||
vtolPathFollowerSettings->HorizontalVelMax);
|
||||
|
||||
|
||||
controlNE.UpdatePositionalParameters(vtolPathFollowerSettings->HorizontalPosP);
|
||||
controlNE.UpdateCommandParameters(-vtolPathFollowerSettings->MaxRollPitch, vtolPathFollowerSettings->MaxRollPitch, vtolPathFollowerSettings->VelocityFeedforward);
|
||||
|
||||
controlDown.UpdateParameters(vtolPathFollowerSettings->LandVerticalVelPID.Kp,
|
||||
vtolPathFollowerSettings->LandVerticalVelPID.Ki,
|
||||
vtolPathFollowerSettings->LandVerticalVelPID.Kd,
|
||||
vtolPathFollowerSettings->LandVerticalVelPID.Beta,
|
||||
dT,
|
||||
vtolPathFollowerSettings->VerticalVelMax);
|
||||
|
||||
// The following is not currently used in the landing control.
|
||||
controlDown.UpdatePositionalParameters(vtolPathFollowerSettings->VerticalPosP);
|
||||
|
||||
VtolSelfTuningStatsData vtolSelfTuningStats;
|
||||
VtolSelfTuningStatsGet(&vtolSelfTuningStats);
|
||||
controlDown.UpdateNeutralThrust(vtolSelfTuningStats.NeutralThrustOffset + vtolPathFollowerSettings->ThrustLimits.Neutral);
|
||||
// initialise limits on thrust but note the FSM can override.
|
||||
controlDown.SetThrustLimits(vtolPathFollowerSettings->ThrustLimits.Min, vtolPathFollowerSettings->ThrustLimits.Max);
|
||||
fsm->SettingsUpdated();
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t VtolLandController::Initialize(VtolPathFollowerSettingsData *ptr_vtolPathFollowerSettings)
|
||||
{
|
||||
PIOS_Assert(ptr_vtolPathFollowerSettings);
|
||||
if (fsm == 0) {
|
||||
fsm = (PathFollowerFSM *)VtolLandFSM::instance();
|
||||
VtolLandFSM::instance()->Initialize(ptr_vtolPathFollowerSettings, pathDesired, flightStatus);
|
||||
vtolPathFollowerSettings = ptr_vtolPathFollowerSettings;
|
||||
controlDown.Initialize(fsm);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
void VtolLandController::UpdateVelocityDesired()
|
||||
{
|
||||
VelocityStateData velocityState;
|
||||
|
||||
VelocityStateGet(&velocityState);
|
||||
VelocityDesiredData velocityDesired;
|
||||
|
||||
controlDown.UpdateVelocityState(velocityState.Down);
|
||||
controlNE.UpdateVelocityState(velocityState.North, velocityState.East);
|
||||
|
||||
// Implement optional horizontal position hold.
|
||||
if (((uint8_t)pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_OPTIONS]) == PATHDESIRED_MODEPARAMETER_LAND_OPTION_HORIZONTAL_PH) {
|
||||
// landing flight mode has stored original horizontal position in pathdesired
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
controlNE.UpdatePositionState(positionState.North, positionState.East);
|
||||
controlNE.ControlPosition();
|
||||
}
|
||||
|
||||
velocityDesired.Down = controlDown.GetVelocityDesired();
|
||||
float north, east;
|
||||
controlNE.GetVelocityDesired(&north, &east);
|
||||
velocityDesired.North = north;
|
||||
velocityDesired.East = east;
|
||||
|
||||
// update pathstatus
|
||||
pathStatus->error = 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;
|
||||
|
||||
|
||||
VelocityDesiredSet(&velocityDesired);
|
||||
}
|
||||
|
||||
int8_t VtolLandController::UpdateStabilizationDesired(bool yaw_attitude, float yaw_direction)
|
||||
{
|
||||
uint8_t result = 1;
|
||||
StabilizationDesiredData stabDesired;
|
||||
AttitudeStateData attitudeState;
|
||||
StabilizationBankData stabSettings;
|
||||
float northCommand;
|
||||
float eastCommand;
|
||||
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
AttitudeStateGet(&attitudeState);
|
||||
StabilizationBankGet(&stabSettings);
|
||||
|
||||
controlNE.GetNECommand(&northCommand, &eastCommand);
|
||||
stabDesired.Thrust = controlDown.GetDownCommand();
|
||||
|
||||
float angle_radians = DEG2RAD(attitudeState.Yaw);
|
||||
float cos_angle = cosf(angle_radians);
|
||||
float sine_angle = sinf(angle_radians);
|
||||
float maxPitch = vtolPathFollowerSettings->MaxRollPitch;
|
||||
stabDesired.StabilizationMode.Pitch = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
|
||||
stabDesired.Pitch = boundf(-northCommand * cos_angle - eastCommand * sine_angle, -maxPitch, maxPitch);
|
||||
stabDesired.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
|
||||
stabDesired.Roll = boundf(-northCommand * sine_angle + eastCommand * cos_angle, -maxPitch, maxPitch);
|
||||
|
||||
ManualControlCommandData manualControl;
|
||||
ManualControlCommandGet(&manualControl);
|
||||
|
||||
if (yaw_attitude) {
|
||||
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
|
||||
stabDesired.Yaw = yaw_direction;
|
||||
} else {
|
||||
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK;
|
||||
stabDesired.Yaw = stabSettings.MaximumRate.Yaw * manualControl.Yaw;
|
||||
}
|
||||
|
||||
// default thrust mode to cruise control
|
||||
stabDesired.StabilizationMode.Thrust = STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL;
|
||||
|
||||
fsm->ConstrainStabiDesired(&stabDesired); // excludes thrust
|
||||
StabilizationDesiredSet(&stabDesired);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
void VtolLandController::UpdateAutoPilot()
|
||||
{
|
||||
fsm->Update();
|
||||
|
||||
UpdateVelocityDesired();
|
||||
|
||||
// yaw behaviour is configurable in vtolpathfollower, select yaw control algorithm
|
||||
bool yaw_attitude = false;
|
||||
float yaw = 0.0f;
|
||||
|
||||
fsm->GetYaw(yaw_attitude, yaw);
|
||||
|
||||
int8_t result = UpdateStabilizationDesired(yaw_attitude, yaw);
|
||||
|
||||
if (!result) {
|
||||
fsm->Abort();
|
||||
}
|
||||
|
||||
if (fsm->GetCurrentState() == PFFSM_STATE_DISARMED) {
|
||||
setArmedIfChanged(FLIGHTSTATUS_ARMED_DISARMED);
|
||||
}
|
||||
|
||||
PathStatusSet(pathStatus);
|
||||
}
|
||||
|
||||
void VtolLandController::setArmedIfChanged(uint8_t val)
|
||||
{
|
||||
if (flightStatus->Armed != val) {
|
||||
flightStatus->Armed = val;
|
||||
FlightStatusSet(flightStatus);
|
||||
}
|
||||
}
|
||||
/*
|
||||
******************************************************************************
|
||||
*
|
||||
* @file vtollandcontroller.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015.
|
||||
* @brief Vtol landing controller loop
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
extern "C" {
|
||||
#include <openpilot.h>
|
||||
|
||||
#include <callbackinfo.h>
|
||||
|
||||
#include <math.h>
|
||||
#include <pid.h>
|
||||
#include <CoordinateConversions.h>
|
||||
#include <sin_lookup.h>
|
||||
#include <pathdesired.h>
|
||||
#include <paths.h>
|
||||
#include "plans.h"
|
||||
#include <sanitycheck.h>
|
||||
|
||||
#include <accelstate.h>
|
||||
#include <vtolpathfollowersettings.h>
|
||||
#include <flightstatus.h>
|
||||
#include <flightmodesettings.h>
|
||||
#include <pathstatus.h>
|
||||
#include <positionstate.h>
|
||||
#include <velocitystate.h>
|
||||
#include <velocitydesired.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <attitudestate.h>
|
||||
#include <takeofflocation.h>
|
||||
#include <manualcontrolcommand.h>
|
||||
#include <systemsettings.h>
|
||||
#include <stabilizationbank.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <vtolselftuningstats.h>
|
||||
#include <pathsummary.h>
|
||||
}
|
||||
|
||||
// C++ includes
|
||||
#include "vtollandcontroller.h"
|
||||
#include "pathfollowerfsm.h"
|
||||
#include "vtollandfsm.h"
|
||||
#include "pidcontroldown.h"
|
||||
|
||||
// Private constants
|
||||
|
||||
// pointer to a singleton instance
|
||||
VtolLandController *VtolLandController::p_inst = 0;
|
||||
|
||||
VtolLandController::VtolLandController()
|
||||
: fsm(NULL), vtolPathFollowerSettings(NULL), mActive(false)
|
||||
{}
|
||||
|
||||
// Called when mode first engaged
|
||||
void VtolLandController::Activate(void)
|
||||
{
|
||||
if (!mActive) {
|
||||
mActive = true;
|
||||
SettingsUpdated();
|
||||
fsm->Activate();
|
||||
controlDown.Activate();
|
||||
controlNE.Activate();
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t VtolLandController::IsActive(void)
|
||||
{
|
||||
return mActive;
|
||||
}
|
||||
|
||||
uint8_t VtolLandController::Mode(void)
|
||||
{
|
||||
return PATHDESIRED_MODE_LAND;
|
||||
}
|
||||
|
||||
// Objective updated in pathdesired, e.g. same flight mode but new target velocity
|
||||
void VtolLandController::ObjectiveUpdated(void)
|
||||
{
|
||||
// Set the objective's target velocity
|
||||
controlDown.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_DOWN]);
|
||||
controlNE.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_NORTH],
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_EAST]);
|
||||
controlNE.UpdatePositionSetpoint(pathDesired->End.North, pathDesired->End.East);
|
||||
}
|
||||
void VtolLandController::Deactivate(void)
|
||||
{
|
||||
if (mActive) {
|
||||
mActive = false;
|
||||
fsm->Inactive();
|
||||
controlDown.Deactivate();
|
||||
controlNE.Deactivate();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void VtolLandController::SettingsUpdated(void)
|
||||
{
|
||||
const float dT = vtolPathFollowerSettings->UpdatePeriod / 1000.0f;
|
||||
|
||||
controlNE.UpdateParameters(vtolPathFollowerSettings->HorizontalVelPID.Kp,
|
||||
vtolPathFollowerSettings->HorizontalVelPID.Ki,
|
||||
vtolPathFollowerSettings->HorizontalVelPID.Kd,
|
||||
vtolPathFollowerSettings->HorizontalVelPID.ILimit,
|
||||
dT,
|
||||
vtolPathFollowerSettings->HorizontalVelMax);
|
||||
|
||||
|
||||
controlNE.UpdatePositionalParameters(vtolPathFollowerSettings->HorizontalPosP);
|
||||
controlNE.UpdateCommandParameters(-vtolPathFollowerSettings->MaxRollPitch, vtolPathFollowerSettings->MaxRollPitch, vtolPathFollowerSettings->VelocityFeedforward);
|
||||
|
||||
controlDown.UpdateParameters(vtolPathFollowerSettings->LandVerticalVelPID.Kp,
|
||||
vtolPathFollowerSettings->LandVerticalVelPID.Ki,
|
||||
vtolPathFollowerSettings->LandVerticalVelPID.Kd,
|
||||
vtolPathFollowerSettings->LandVerticalVelPID.Beta,
|
||||
dT,
|
||||
vtolPathFollowerSettings->VerticalVelMax);
|
||||
|
||||
// The following is not currently used in the landing control.
|
||||
controlDown.UpdatePositionalParameters(vtolPathFollowerSettings->VerticalPosP);
|
||||
|
||||
VtolSelfTuningStatsData vtolSelfTuningStats;
|
||||
VtolSelfTuningStatsGet(&vtolSelfTuningStats);
|
||||
controlDown.UpdateNeutralThrust(vtolSelfTuningStats.NeutralThrustOffset + vtolPathFollowerSettings->ThrustLimits.Neutral);
|
||||
// initialise limits on thrust but note the FSM can override.
|
||||
controlDown.SetThrustLimits(vtolPathFollowerSettings->ThrustLimits.Min, vtolPathFollowerSettings->ThrustLimits.Max);
|
||||
fsm->SettingsUpdated();
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t VtolLandController::Initialize(VtolPathFollowerSettingsData *ptr_vtolPathFollowerSettings)
|
||||
{
|
||||
PIOS_Assert(ptr_vtolPathFollowerSettings);
|
||||
if (fsm == 0) {
|
||||
fsm = (PathFollowerFSM *)VtolLandFSM::instance();
|
||||
VtolLandFSM::instance()->Initialize(ptr_vtolPathFollowerSettings, pathDesired, flightStatus);
|
||||
vtolPathFollowerSettings = ptr_vtolPathFollowerSettings;
|
||||
controlDown.Initialize(fsm);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
void VtolLandController::UpdateVelocityDesired()
|
||||
{
|
||||
VelocityStateData velocityState;
|
||||
|
||||
VelocityStateGet(&velocityState);
|
||||
VelocityDesiredData velocityDesired;
|
||||
|
||||
controlDown.UpdateVelocityState(velocityState.Down);
|
||||
controlNE.UpdateVelocityState(velocityState.North, velocityState.East);
|
||||
|
||||
// Implement optional horizontal position hold.
|
||||
if ((((uint8_t)pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_OPTIONS]) == PATHDESIRED_MODEPARAMETER_LAND_OPTION_HORIZONTAL_PH) ||
|
||||
(flightStatus->ControlChain.PathPlanner == FLIGHTSTATUS_CONTROLCHAIN_TRUE)) {
|
||||
// landing flight mode has stored original horizontal position in pathdesired
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
controlNE.UpdatePositionState(positionState.North, positionState.East);
|
||||
controlNE.ControlPosition();
|
||||
}
|
||||
|
||||
velocityDesired.Down = controlDown.GetVelocityDesired();
|
||||
float north, east;
|
||||
controlNE.GetVelocityDesired(&north, &east);
|
||||
velocityDesired.North = north;
|
||||
velocityDesired.East = east;
|
||||
|
||||
// update pathstatus
|
||||
pathStatus->error = 0.0f;
|
||||
pathStatus->fractional_progress = 0.0f;
|
||||
if (fsm->GetCurrentState() == PFFSM_STATE_DISARMED) {
|
||||
pathStatus->fractional_progress = 1.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;
|
||||
|
||||
|
||||
VelocityDesiredSet(&velocityDesired);
|
||||
}
|
||||
|
||||
int8_t VtolLandController::UpdateStabilizationDesired(bool yaw_attitude, float yaw_direction)
|
||||
{
|
||||
uint8_t result = 1;
|
||||
StabilizationDesiredData stabDesired;
|
||||
AttitudeStateData attitudeState;
|
||||
StabilizationBankData stabSettings;
|
||||
float northCommand;
|
||||
float eastCommand;
|
||||
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
AttitudeStateGet(&attitudeState);
|
||||
StabilizationBankGet(&stabSettings);
|
||||
|
||||
controlNE.GetNECommand(&northCommand, &eastCommand);
|
||||
stabDesired.Thrust = controlDown.GetDownCommand();
|
||||
|
||||
float angle_radians = DEG2RAD(attitudeState.Yaw);
|
||||
float cos_angle = cosf(angle_radians);
|
||||
float sine_angle = sinf(angle_radians);
|
||||
float maxPitch = vtolPathFollowerSettings->MaxRollPitch;
|
||||
stabDesired.StabilizationMode.Pitch = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
|
||||
stabDesired.Pitch = boundf(-northCommand * cos_angle - eastCommand * sine_angle, -maxPitch, maxPitch);
|
||||
stabDesired.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
|
||||
stabDesired.Roll = boundf(-northCommand * sine_angle + eastCommand * cos_angle, -maxPitch, maxPitch);
|
||||
|
||||
ManualControlCommandData manualControl;
|
||||
ManualControlCommandGet(&manualControl);
|
||||
|
||||
if (yaw_attitude) {
|
||||
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE;
|
||||
stabDesired.Yaw = yaw_direction;
|
||||
} else {
|
||||
stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK;
|
||||
stabDesired.Yaw = stabSettings.MaximumRate.Yaw * manualControl.Yaw;
|
||||
}
|
||||
|
||||
// default thrust mode to cruise control
|
||||
stabDesired.StabilizationMode.Thrust = STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL;
|
||||
|
||||
fsm->ConstrainStabiDesired(&stabDesired); // excludes thrust
|
||||
StabilizationDesiredSet(&stabDesired);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
void VtolLandController::UpdateAutoPilot()
|
||||
{
|
||||
fsm->Update();
|
||||
|
||||
UpdateVelocityDesired();
|
||||
|
||||
// yaw behaviour is configurable in vtolpathfollower, select yaw control algorithm
|
||||
bool yaw_attitude = false;
|
||||
float yaw = 0.0f;
|
||||
|
||||
fsm->GetYaw(yaw_attitude, yaw);
|
||||
|
||||
int8_t result = UpdateStabilizationDesired(yaw_attitude, yaw);
|
||||
|
||||
if (!result) {
|
||||
fsm->Abort();
|
||||
}
|
||||
|
||||
PathStatusSet(pathStatus);
|
||||
}
|
||||
|
@ -1,703 +1,701 @@
|
||||
/*
|
||||
******************************************************************************
|
||||
*
|
||||
* @file vtollandfsm.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015.
|
||||
* @brief This landing state machine is a helper state machine to the
|
||||
* VtolLandController.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
extern "C" {
|
||||
#include <openpilot.h>
|
||||
|
||||
#include <callbackinfo.h>
|
||||
|
||||
#include <math.h>
|
||||
#include <pid.h>
|
||||
#include <CoordinateConversions.h>
|
||||
#include <sin_lookup.h>
|
||||
#include <pathdesired.h>
|
||||
#include <paths.h>
|
||||
#include "plans.h"
|
||||
#include <sanitycheck.h>
|
||||
|
||||
#include <homelocation.h>
|
||||
#include <accelstate.h>
|
||||
#include <fixedwingpathfollowersettings.h>
|
||||
#include <fixedwingpathfollowerstatus.h>
|
||||
#include <vtolpathfollowersettings.h>
|
||||
#include <flightstatus.h>
|
||||
#include <flightmodesettings.h>
|
||||
#include <pathstatus.h>
|
||||
#include <positionstate.h>
|
||||
#include <velocitystate.h>
|
||||
#include <velocitydesired.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <airspeedstate.h>
|
||||
#include <attitudestate.h>
|
||||
#include <takeofflocation.h>
|
||||
#include <poilocation.h>
|
||||
#include <manualcontrolcommand.h>
|
||||
#include <systemsettings.h>
|
||||
#include <stabilizationbank.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <vtolselftuningstats.h>
|
||||
#include <statusvtolland.h>
|
||||
#include <pathsummary.h>
|
||||
}
|
||||
|
||||
// C++ includes
|
||||
#include <vtollandfsm.h>
|
||||
|
||||
|
||||
// Private constants
|
||||
#define TIMER_COUNT_PER_SECOND (1000 / vtolPathFollowerSettings->UpdatePeriod)
|
||||
#define MIN_LANDRATE 0.1f
|
||||
#define MAX_LANDRATE 0.6f
|
||||
#define LOW_ALT_DESCENT_REDUCTION_FACTOR 0.7f // TODO Need to make the transition smooth
|
||||
#define LANDRATE_LOWLIMIT_FACTOR 0.5f
|
||||
#define LANDRATE_HILIMIT_FACTOR 1.5f
|
||||
#define TIMEOUT_INIT_ALTHOLD (3 * TIMER_COUNT_PER_SECOND)
|
||||
#define TIMEOUT_WTG_FOR_DESCENTRATE (10 * TIMER_COUNT_PER_SECOND)
|
||||
#define WTG_FOR_DESCENTRATE_COUNT_LIMIT 10
|
||||
#define TIMEOUT_AT_DESCENTRATE 10
|
||||
#define TIMEOUT_GROUNDEFFECT (1 * TIMER_COUNT_PER_SECOND)
|
||||
#define TIMEOUT_THRUSTDOWN (2 * TIMER_COUNT_PER_SECOND)
|
||||
#define LANDING_PID_SCALAR_P 2.0f
|
||||
#define LANDING_PID_SCALAR_I 10.0f
|
||||
#define LANDING_SLOWDOWN_HEIGHT -5.0f
|
||||
#define BOUNCE_VELOCITY_TRIGGER_LIMIT -0.3f
|
||||
#define BOUNCE_ACCELERATION_TRIGGER_LIMIT -6.0f
|
||||
#define BOUNCE_TRIGGER_COUNT 4
|
||||
#define GROUNDEFFECT_SLOWDOWN_FACTOR 0.3f
|
||||
#define GROUNDEFFECT_SLOWDOWN_COUNT 4
|
||||
|
||||
VtolLandFSM::PathFollowerFSM_LandStateHandler_T VtolLandFSM::sLandStateTable[LAND_STATE_SIZE] = {
|
||||
[LAND_STATE_INACTIVE] = { .setup = &VtolLandFSM::setup_inactive, .run = 0 },
|
||||
[LAND_STATE_INIT_ALTHOLD] = { .setup = &VtolLandFSM::setup_init_althold, .run = &VtolLandFSM::run_init_althold },
|
||||
[LAND_STATE_WTG_FOR_DESCENTRATE] = { .setup = &VtolLandFSM::setup_wtg_for_descentrate, .run = &VtolLandFSM::run_wtg_for_descentrate },
|
||||
[LAND_STATE_AT_DESCENTRATE] = { .setup = &VtolLandFSM::setup_at_descentrate, .run = &VtolLandFSM::run_at_descentrate },
|
||||
[LAND_STATE_WTG_FOR_GROUNDEFFECT] = { .setup = &VtolLandFSM::setup_wtg_for_groundeffect, .run = &VtolLandFSM::run_wtg_for_groundeffect },
|
||||
[LAND_STATE_GROUNDEFFECT] = { .setup = &VtolLandFSM::setup_groundeffect, .run = &VtolLandFSM::run_groundeffect },
|
||||
[LAND_STATE_THRUSTDOWN] = { .setup = &VtolLandFSM::setup_thrustdown, .run = &VtolLandFSM::run_thrustdown },
|
||||
[LAND_STATE_THRUSTOFF] = { .setup = &VtolLandFSM::setup_thrustoff, .run = &VtolLandFSM::run_thrustoff },
|
||||
[LAND_STATE_DISARMED] = { .setup = &VtolLandFSM::setup_disarmed, .run = &VtolLandFSM::run_disarmed },
|
||||
[LAND_STATE_ABORT] = { .setup = &VtolLandFSM::setup_abort, .run = &VtolLandFSM::run_abort }
|
||||
};
|
||||
|
||||
// pointer to a singleton instance
|
||||
VtolLandFSM *VtolLandFSM::p_inst = 0;
|
||||
|
||||
|
||||
VtolLandFSM::VtolLandFSM()
|
||||
: mLandData(0), vtolPathFollowerSettings(0), pathDesired(0), flightStatus(0)
|
||||
{}
|
||||
|
||||
// Private types
|
||||
|
||||
// Private functions
|
||||
// Public API methods
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t VtolLandFSM::Initialize(VtolPathFollowerSettingsData *ptr_vtolPathFollowerSettings,
|
||||
PathDesiredData *ptr_pathDesired,
|
||||
FlightStatusData *ptr_flightStatus)
|
||||
{
|
||||
PIOS_Assert(ptr_vtolPathFollowerSettings);
|
||||
PIOS_Assert(ptr_pathDesired);
|
||||
PIOS_Assert(ptr_flightStatus);
|
||||
|
||||
if (mLandData == 0) {
|
||||
mLandData = (VtolLandFSMData_T *)pios_malloc(sizeof(VtolLandFSMData_T));
|
||||
PIOS_Assert(mLandData);
|
||||
}
|
||||
memset(mLandData, sizeof(VtolLandFSMData_T), 0);
|
||||
vtolPathFollowerSettings = ptr_vtolPathFollowerSettings;
|
||||
pathDesired = ptr_pathDesired;
|
||||
flightStatus = ptr_flightStatus;
|
||||
initFSM();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void VtolLandFSM::Inactive(void)
|
||||
{
|
||||
memset(mLandData, sizeof(VtolLandFSMData_T), 0);
|
||||
initFSM();
|
||||
}
|
||||
|
||||
// Initialise the FSM
|
||||
void VtolLandFSM::initFSM(void)
|
||||
{
|
||||
if (vtolPathFollowerSettings != 0) {
|
||||
setState(LAND_STATE_INACTIVE, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
} else {
|
||||
mLandData->currentState = LAND_STATE_INACTIVE;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::Activate()
|
||||
{
|
||||
memset(mLandData, sizeof(VtolLandFSMData_T), 0);
|
||||
mLandData->currentState = LAND_STATE_INACTIVE;
|
||||
mLandData->flLowAltitude = false;
|
||||
mLandData->flAltitudeHold = false;
|
||||
mLandData->fsmLandStatus.averageDescentRate = MIN_LANDRATE;
|
||||
mLandData->fsmLandStatus.averageDescentThrust = vtolPathFollowerSettings->ThrustLimits.Neutral;
|
||||
mLandData->fsmLandStatus.calculatedNeutralThrust = vtolPathFollowerSettings->ThrustLimits.Neutral;
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
TakeOffLocationGet(&(mLandData->takeOffLocation));
|
||||
mLandData->fsmLandStatus.AltitudeAtState[LAND_STATE_INACTIVE] = 0.0f;
|
||||
assessAltitude();
|
||||
|
||||
if (pathDesired->Mode == PATHDESIRED_MODE_LAND) {
|
||||
#ifndef DEBUG_GROUNDIMPACT
|
||||
setState(LAND_STATE_INIT_ALTHOLD, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
#else
|
||||
setState(LAND_STATE_WTG_FOR_GROUNDEFFECT, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
#endif
|
||||
} else {
|
||||
// move to error state and callback to position hold
|
||||
setState(LAND_STATE_ABORT, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::Abort(void)
|
||||
{
|
||||
setState(LAND_STATE_ABORT, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
}
|
||||
|
||||
PathFollowerFSMState_T VtolLandFSM::GetCurrentState(void)
|
||||
{
|
||||
switch (mLandData->currentState) {
|
||||
case LAND_STATE_INACTIVE:
|
||||
return PFFSM_STATE_INACTIVE;
|
||||
|
||||
break;
|
||||
case LAND_STATE_ABORT:
|
||||
return PFFSM_STATE_ABORT;
|
||||
|
||||
break;
|
||||
case LAND_STATE_DISARMED:
|
||||
return PFFSM_STATE_DISARMED;
|
||||
|
||||
break;
|
||||
default:
|
||||
return PFFSM_STATE_ACTIVE;
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::Update()
|
||||
{
|
||||
runState();
|
||||
if (GetCurrentState() != PFFSM_STATE_INACTIVE) {
|
||||
runAlways();
|
||||
}
|
||||
}
|
||||
|
||||
int32_t VtolLandFSM::runState(void)
|
||||
{
|
||||
uint8_t flTimeout = false;
|
||||
|
||||
mLandData->stateRunCount++;
|
||||
|
||||
if (mLandData->stateTimeoutCount > 0 && mLandData->stateRunCount > mLandData->stateTimeoutCount) {
|
||||
flTimeout = true;
|
||||
}
|
||||
|
||||
// If the current state has a static function, call it
|
||||
if (sLandStateTable[mLandData->currentState].run) {
|
||||
(this->*sLandStateTable[mLandData->currentState].run)(flTimeout);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t VtolLandFSM::runAlways(void)
|
||||
{
|
||||
void assessAltitude(void);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
// PathFollower implements the PID scheme and has a objective
|
||||
// set by a PathDesired object. Based on the mode, pathfollower
|
||||
// uses FSM's as helper functions that manage state and event detection.
|
||||
// PathFollower calls into FSM methods to alter its commands.
|
||||
|
||||
void VtolLandFSM::BoundThrust(float &ulow, float &uhigh)
|
||||
{
|
||||
ulow = mLandData->boundThrustMin;
|
||||
uhigh = mLandData->boundThrustMax;
|
||||
|
||||
|
||||
if (mLandData->flConstrainThrust) {
|
||||
uhigh = mLandData->thrustLimit;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::ConstrainStabiDesired(StabilizationDesiredData *stabDesired)
|
||||
{
|
||||
if (mLandData->flZeroStabiHorizontal && stabDesired) {
|
||||
stabDesired->Pitch = 0.0f;
|
||||
stabDesired->Roll = 0.0f;
|
||||
stabDesired->Yaw = 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::CheckPidScaler(pid_scaler *local_scaler)
|
||||
{
|
||||
if (mLandData->flLowAltitude) {
|
||||
local_scaler->p = LANDING_PID_SCALAR_P;
|
||||
local_scaler->i = LANDING_PID_SCALAR_I;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Set the new state and perform setup for subsequent state run calls
|
||||
// This is called by state run functions on event detection that drive
|
||||
// state transitions.
|
||||
void VtolLandFSM::setState(PathFollowerFSM_LandState_T newState, StatusVtolLandStateExitReasonOptions reason)
|
||||
{
|
||||
mLandData->fsmLandStatus.StateExitReason[mLandData->currentState] = reason;
|
||||
|
||||
if (mLandData->currentState == newState) {
|
||||
return;
|
||||
}
|
||||
mLandData->currentState = newState;
|
||||
|
||||
if (newState != LAND_STATE_INACTIVE) {
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
float takeOffDown = 0.0f;
|
||||
if (mLandData->takeOffLocation.Status == TAKEOFFLOCATION_STATUS_VALID) {
|
||||
takeOffDown = mLandData->takeOffLocation.Down;
|
||||
}
|
||||
mLandData->fsmLandStatus.AltitudeAtState[newState] = positionState.Down - takeOffDown;
|
||||
assessAltitude();
|
||||
}
|
||||
|
||||
// Restart state timer counter
|
||||
mLandData->stateRunCount = 0;
|
||||
|
||||
// Reset state timeout to disabled/zero
|
||||
mLandData->stateTimeoutCount = 0;
|
||||
|
||||
if (sLandStateTable[mLandData->currentState].setup) {
|
||||
(this->*sLandStateTable[mLandData->currentState].setup)();
|
||||
}
|
||||
|
||||
updateVtolLandFSMStatus();
|
||||
}
|
||||
|
||||
|
||||
// Timeout utility function for use by state init implementations
|
||||
void VtolLandFSM::setStateTimeout(int32_t count)
|
||||
{
|
||||
mLandData->stateTimeoutCount = count;
|
||||
}
|
||||
|
||||
void VtolLandFSM::updateVtolLandFSMStatus()
|
||||
{
|
||||
mLandData->fsmLandStatus.State = mLandData->currentState;
|
||||
if (mLandData->flLowAltitude) {
|
||||
mLandData->fsmLandStatus.AltitudeState = STATUSVTOLLAND_ALTITUDESTATE_LOW;
|
||||
} else {
|
||||
mLandData->fsmLandStatus.AltitudeState = STATUSVTOLLAND_ALTITUDESTATE_HIGH;
|
||||
}
|
||||
StatusVtolLandSet(&mLandData->fsmLandStatus);
|
||||
}
|
||||
|
||||
|
||||
float VtolLandFSM::BoundVelocityDown(float velocity_down)
|
||||
{
|
||||
velocity_down = boundf(velocity_down, MIN_LANDRATE, MAX_LANDRATE);
|
||||
if (mLandData->flLowAltitude) {
|
||||
velocity_down *= LOW_ALT_DESCENT_REDUCTION_FACTOR;
|
||||
}
|
||||
mLandData->fsmLandStatus.targetDescentRate = velocity_down;
|
||||
|
||||
if (mLandData->flAltitudeHold) {
|
||||
return 0.0f;
|
||||
} else {
|
||||
return velocity_down;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::assessAltitude(void)
|
||||
{
|
||||
float positionDown;
|
||||
|
||||
PositionStateDownGet(&positionDown);
|
||||
float takeOffDown = 0.0f;
|
||||
if (mLandData->takeOffLocation.Status == TAKEOFFLOCATION_STATUS_VALID) {
|
||||
takeOffDown = mLandData->takeOffLocation.Down;
|
||||
}
|
||||
float positionDownRelativeToTakeoff = positionDown - takeOffDown;
|
||||
if (positionDownRelativeToTakeoff < LANDING_SLOWDOWN_HEIGHT) {
|
||||
mLandData->flLowAltitude = false;
|
||||
} else {
|
||||
mLandData->flLowAltitude = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// FSM Setup and Run method implementation
|
||||
|
||||
// State: INACTIVE
|
||||
void VtolLandFSM::setup_inactive(void)
|
||||
{
|
||||
// Re-initialise local variables
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->flConstrainThrust = false;
|
||||
}
|
||||
|
||||
// State: INIT ALTHOLD
|
||||
void VtolLandFSM::setup_init_althold(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_INIT_ALTHOLD);
|
||||
// get target descent velocity
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->fsmLandStatus.targetDescentRate = BoundVelocityDown(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_VELOCITYVECTOR_DOWN]);
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->flAltitudeHold = true;
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_init_althold(uint8_t flTimeout)
|
||||
{
|
||||
if (flTimeout) {
|
||||
mLandData->flAltitudeHold = false;
|
||||
setState(LAND_STATE_WTG_FOR_DESCENTRATE, STATUSVTOLLAND_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// State: WAITING FOR DESCENT RATE
|
||||
void VtolLandFSM::setup_wtg_for_descentrate(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_WTG_FOR_DESCENTRATE);
|
||||
// get target descent velocity
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->observationCount = 0;
|
||||
mLandData->observation2Count = 0;
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->flAltitudeHold = false;
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_wtg_for_descentrate(uint8_t flTimeout)
|
||||
{
|
||||
// Look at current actual thrust...are we already shutdown??
|
||||
VelocityStateData velocityState;
|
||||
|
||||
VelocityStateGet(&velocityState);
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
|
||||
// We don't expect PID to get exactly the target descent rate, so have a lower
|
||||
// water mark but need to see 5 observations to be confident that we have semi-stable
|
||||
// descent achieved
|
||||
|
||||
// we need to see velocity down within a range of control before we proceed, without which we
|
||||
// really don't have confidence to allow later states to run.
|
||||
if (velocityState.Down > (LANDRATE_LOWLIMIT_FACTOR * mLandData->fsmLandStatus.targetDescentRate) &&
|
||||
velocityState.Down < (LANDRATE_HILIMIT_FACTOR * mLandData->fsmLandStatus.targetDescentRate)) {
|
||||
if (mLandData->observationCount++ > WTG_FOR_DESCENTRATE_COUNT_LIMIT) {
|
||||
setState(LAND_STATE_AT_DESCENTRATE, STATUSVTOLLAND_STATEEXITREASON_DESCENTRATEOK);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
if (flTimeout) {
|
||||
setState(LAND_STATE_ABORT, STATUSVTOLLAND_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// State: AT DESCENT RATE
|
||||
void VtolLandFSM::setup_at_descentrate(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_AT_DESCENTRATE);
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->observationCount = 0;
|
||||
mLandData->sum1 = 0.0f;
|
||||
mLandData->sum2 = 0.0f;
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->fsmLandStatus.averageDescentRate = MIN_LANDRATE;
|
||||
mLandData->fsmLandStatus.averageDescentThrust = vtolPathFollowerSettings->ThrustLimits.Neutral;
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_at_descentrate(uint8_t flTimeout)
|
||||
{
|
||||
VelocityStateData velocityState;
|
||||
|
||||
VelocityStateGet(&velocityState);
|
||||
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
|
||||
mLandData->sum1 += velocityState.Down;
|
||||
mLandData->sum2 += stabDesired.Thrust;
|
||||
mLandData->observationCount++;
|
||||
if (flTimeout) {
|
||||
mLandData->fsmLandStatus.averageDescentRate = boundf((mLandData->sum1 / (float)(mLandData->observationCount)), 0.5f * MIN_LANDRATE, 1.5f * MAX_LANDRATE);
|
||||
mLandData->fsmLandStatus.averageDescentThrust = boundf((mLandData->sum2 / (float)(mLandData->observationCount)), vtolPathFollowerSettings->ThrustLimits.Min, vtolPathFollowerSettings->ThrustLimits.Max);
|
||||
|
||||
// We need to calculate a neutral limit to use later to constrain upper thrust range during states where we are close to the ground
|
||||
// As our battery gets flat, ThrustLimits.Neutral needs to constrain us too much and we get too fast a descent rate. We can
|
||||
// detect this by the fact that the descent rate will exceed the target and the required thrust will exceed the neutral value
|
||||
mLandData->fsmLandStatus.calculatedNeutralThrust = mLandData->fsmLandStatus.averageDescentRate / mLandData->fsmLandStatus.targetDescentRate * mLandData->fsmLandStatus.averageDescentThrust;
|
||||
mLandData->fsmLandStatus.calculatedNeutralThrust = boundf(mLandData->fsmLandStatus.calculatedNeutralThrust, vtolPathFollowerSettings->ThrustLimits.Neutral, vtolPathFollowerSettings->ThrustLimits.Max);
|
||||
|
||||
|
||||
setState(LAND_STATE_WTG_FOR_GROUNDEFFECT, STATUSVTOLLAND_STATEEXITREASON_DESCENTRATEOK);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// State: WAITING FOR GROUND EFFECT
|
||||
void VtolLandFSM::setup_wtg_for_groundeffect(void)
|
||||
{
|
||||
// No timeout
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->observationCount = 0;
|
||||
mLandData->observation2Count = 0;
|
||||
mLandData->sum1 = 0.0f;
|
||||
mLandData->sum2 = 0.0f;
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceVelocity = 0.0f;
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceAccel = 0.0f;
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_wtg_for_groundeffect(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
// detect material downrating in thrust for 1 second.
|
||||
VelocityStateData velocityState;
|
||||
|
||||
VelocityStateGet(&velocityState);
|
||||
AccelStateData accelState;
|
||||
AccelStateGet(&accelState);
|
||||
|
||||
// +ve 9.8 expected
|
||||
float g_e;
|
||||
HomeLocationg_eGet(&g_e);
|
||||
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
|
||||
// detect bounce
|
||||
uint8_t flBounce = (velocityState.Down < BOUNCE_VELOCITY_TRIGGER_LIMIT);
|
||||
if (flBounce) {
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceVelocity = velocityState.Down;
|
||||
} else {
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceVelocity = 0.0f;
|
||||
}
|
||||
|
||||
// invert sign of accel to the standard convention of down is +ve and subtract the gravity to get
|
||||
// a relative acceleration term.
|
||||
float bounceAccel = -accelState.z - g_e;
|
||||
uint8_t flBounceAccel = (bounceAccel < BOUNCE_ACCELERATION_TRIGGER_LIMIT);
|
||||
if (flBounceAccel) {
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceAccel = bounceAccel;
|
||||
} else {
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceAccel = 0.0f;
|
||||
}
|
||||
|
||||
if (flBounce || flBounceAccel) {
|
||||
mLandData->observation2Count++;
|
||||
if (mLandData->observation2Count > BOUNCE_TRIGGER_COUNT) {
|
||||
setState(LAND_STATE_GROUNDEFFECT, (flBounce ? STATUSVTOLLAND_STATEEXITREASON_BOUNCEVELOCITY : STATUSVTOLLAND_STATEEXITREASON_BOUNCEACCEL));
|
||||
return;
|
||||
}
|
||||
} else {
|
||||
mLandData->observation2Count = 0;
|
||||
}
|
||||
|
||||
// detect low descent rate
|
||||
uint8_t flDescentRateLow = (velocityState.Down < (GROUNDEFFECT_SLOWDOWN_FACTOR * mLandData->fsmLandStatus.averageDescentRate));
|
||||
if (flDescentRateLow) {
|
||||
mLandData->boundThrustMax = mLandData->fsmLandStatus.calculatedNeutralThrust;
|
||||
mLandData->observationCount++;
|
||||
if (mLandData->observationCount > GROUNDEFFECT_SLOWDOWN_COUNT) {
|
||||
#ifndef DEBUG_GROUNDIMPACT
|
||||
setState(LAND_STATE_GROUNDEFFECT, STATUSVTOLLAND_STATEEXITREASON_LOWDESCENTRATE);
|
||||
#endif
|
||||
return;
|
||||
}
|
||||
} else {
|
||||
mLandData->observationCount = 0;
|
||||
}
|
||||
|
||||
updateVtolLandFSMStatus();
|
||||
}
|
||||
|
||||
// STATE: GROUNDEFFET
|
||||
void VtolLandFSM::setup_groundeffect(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_GROUNDEFFECT);
|
||||
mLandData->flZeroStabiHorizontal = true;
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
mLandData->expectedLandPositionNorth = positionState.North;
|
||||
mLandData->expectedLandPositionEast = positionState.East;
|
||||
mLandData->flConstrainThrust = false;
|
||||
|
||||
// now that we have ground effect limit max thrust to neutral
|
||||
mLandData->boundThrustMin = -0.1f;
|
||||
mLandData->boundThrustMax = mLandData->fsmLandStatus.calculatedNeutralThrust;
|
||||
}
|
||||
void VtolLandFSM::run_groundeffect(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
StabilizationDesiredData stabDesired;
|
||||
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
if (stabDesired.Thrust < 0.0f) {
|
||||
setState(LAND_STATE_THRUSTOFF, STATUSVTOLLAND_STATEEXITREASON_ZEROTHRUST);
|
||||
return;
|
||||
}
|
||||
|
||||
// Stay in this state until we get a low altitude flag.
|
||||
if (mLandData->flLowAltitude == false) {
|
||||
// worst case scenario is that we land and the pid brings thrust down to zero.
|
||||
return;
|
||||
}
|
||||
|
||||
// detect broad sideways drift. If for some reason we have a hard landing that the bounce detection misses, this will kick in
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
float north_error = mLandData->expectedLandPositionNorth - positionState.North;
|
||||
float east_error = mLandData->expectedLandPositionEast - positionState.East;
|
||||
float positionError = sqrtf(north_error * north_error + east_error * east_error);
|
||||
if (positionError > 0.3f) {
|
||||
setState(LAND_STATE_THRUSTDOWN, STATUSVTOLLAND_STATEEXITREASON_POSITIONERROR);
|
||||
return;
|
||||
}
|
||||
|
||||
if (flTimeout) {
|
||||
setState(LAND_STATE_THRUSTDOWN, STATUSVTOLLAND_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
// STATE: THRUSTDOWN
|
||||
void VtolLandFSM::setup_thrustdown(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_THRUSTDOWN);
|
||||
mLandData->flZeroStabiHorizontal = true;
|
||||
mLandData->flConstrainThrust = true;
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
mLandData->thrustLimit = stabDesired.Thrust;
|
||||
mLandData->sum1 = stabDesired.Thrust / (float)TIMEOUT_THRUSTDOWN;
|
||||
mLandData->boundThrustMin = -0.1f;
|
||||
mLandData->boundThrustMax = mLandData->fsmLandStatus.calculatedNeutralThrust;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_thrustdown(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
// reduce thrust setpoint step by step
|
||||
mLandData->thrustLimit -= mLandData->sum1;
|
||||
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
if (stabDesired.Thrust < 0.0f || mLandData->thrustLimit < 0.0f) {
|
||||
setState(LAND_STATE_THRUSTOFF, STATUSVTOLLAND_STATEEXITREASON_ZEROTHRUST);
|
||||
}
|
||||
|
||||
if (flTimeout) {
|
||||
setState(LAND_STATE_THRUSTOFF, STATUSVTOLLAND_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
// STATE: THRUSTOFF
|
||||
void VtolLandFSM::setup_thrustoff(void)
|
||||
{
|
||||
mLandData->thrustLimit = -1.0f;
|
||||
mLandData->flConstrainThrust = true;
|
||||
mLandData->boundThrustMin = -0.1f;
|
||||
mLandData->boundThrustMax = 0.0f;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_thrustoff(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
setState(LAND_STATE_DISARMED, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
}
|
||||
|
||||
// STATE: DISARMED
|
||||
void VtolLandFSM::setup_disarmed(void)
|
||||
{
|
||||
// nothing to do
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->observationCount = 0;
|
||||
mLandData->boundThrustMin = -0.1f;
|
||||
mLandData->boundThrustMax = 0.0f;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_disarmed(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
#ifdef DEBUG_GROUNDIMPACT
|
||||
if (mLandData->observationCount++ > 100) {
|
||||
setState(LAND_STATE_WTG_FOR_GROUNDEFFECT, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void VtolLandFSM::fallback_to_hold(void)
|
||||
{
|
||||
PositionStateData positionState;
|
||||
|
||||
PositionStateGet(&positionState);
|
||||
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_GOTOENDPOINT;
|
||||
|
||||
PathDesiredSet(pathDesired);
|
||||
}
|
||||
|
||||
// abort repeatedly overwrites pathfollower's objective on a landing abort and
|
||||
// continues to do so until a flight mode change.
|
||||
void VtolLandFSM::setup_abort(void)
|
||||
{
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
fallback_to_hold();
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_abort(__attribute__((unused)) uint8_t flTimeout)
|
||||
{}
|
||||
/*
|
||||
******************************************************************************
|
||||
*
|
||||
* @file vtollandfsm.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015.
|
||||
* @brief This landing state machine is a helper state machine to the
|
||||
* VtolLandController.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
extern "C" {
|
||||
#include <openpilot.h>
|
||||
|
||||
#include <callbackinfo.h>
|
||||
|
||||
#include <math.h>
|
||||
#include <pid.h>
|
||||
#include <CoordinateConversions.h>
|
||||
#include <sin_lookup.h>
|
||||
#include <pathdesired.h>
|
||||
#include <paths.h>
|
||||
#include "plans.h"
|
||||
#include <sanitycheck.h>
|
||||
|
||||
#include <homelocation.h>
|
||||
#include <accelstate.h>
|
||||
#include <vtolpathfollowersettings.h>
|
||||
#include <flightstatus.h>
|
||||
#include <flightmodesettings.h>
|
||||
#include <pathstatus.h>
|
||||
#include <positionstate.h>
|
||||
#include <velocitystate.h>
|
||||
#include <velocitydesired.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <airspeedstate.h>
|
||||
#include <attitudestate.h>
|
||||
#include <takeofflocation.h>
|
||||
#include <poilocation.h>
|
||||
#include <manualcontrolcommand.h>
|
||||
#include <systemsettings.h>
|
||||
#include <stabilizationbank.h>
|
||||
#include <stabilizationdesired.h>
|
||||
#include <vtolselftuningstats.h>
|
||||
#include <statusvtolland.h>
|
||||
#include <pathsummary.h>
|
||||
}
|
||||
|
||||
// C++ includes
|
||||
#include <vtollandfsm.h>
|
||||
|
||||
|
||||
// Private constants
|
||||
#define TIMER_COUNT_PER_SECOND (1000 / vtolPathFollowerSettings->UpdatePeriod)
|
||||
#define MIN_LANDRATE 0.1f
|
||||
#define MAX_LANDRATE 0.6f
|
||||
#define LOW_ALT_DESCENT_REDUCTION_FACTOR 0.7f // TODO Need to make the transition smooth
|
||||
#define LANDRATE_LOWLIMIT_FACTOR 0.5f
|
||||
#define LANDRATE_HILIMIT_FACTOR 1.5f
|
||||
#define TIMEOUT_INIT_ALTHOLD (3 * TIMER_COUNT_PER_SECOND)
|
||||
#define TIMEOUT_WTG_FOR_DESCENTRATE (10 * TIMER_COUNT_PER_SECOND)
|
||||
#define WTG_FOR_DESCENTRATE_COUNT_LIMIT 10
|
||||
#define TIMEOUT_AT_DESCENTRATE 10
|
||||
#define TIMEOUT_GROUNDEFFECT (1 * TIMER_COUNT_PER_SECOND)
|
||||
#define TIMEOUT_THRUSTDOWN (2 * TIMER_COUNT_PER_SECOND)
|
||||
#define LANDING_PID_SCALAR_P 2.0f
|
||||
#define LANDING_PID_SCALAR_I 10.0f
|
||||
#define LANDING_SLOWDOWN_HEIGHT -5.0f
|
||||
#define BOUNCE_VELOCITY_TRIGGER_LIMIT -0.3f
|
||||
#define BOUNCE_ACCELERATION_TRIGGER_LIMIT -9.0f // -6.0 found to be too sensitive
|
||||
#define BOUNCE_TRIGGER_COUNT 4
|
||||
#define GROUNDEFFECT_SLOWDOWN_FACTOR 0.3f
|
||||
#define GROUNDEFFECT_SLOWDOWN_COUNT 4
|
||||
|
||||
VtolLandFSM::PathFollowerFSM_LandStateHandler_T VtolLandFSM::sLandStateTable[LAND_STATE_SIZE] = {
|
||||
[LAND_STATE_INACTIVE] = { .setup = &VtolLandFSM::setup_inactive, .run = 0 },
|
||||
[LAND_STATE_INIT_ALTHOLD] = { .setup = &VtolLandFSM::setup_init_althold, .run = &VtolLandFSM::run_init_althold },
|
||||
[LAND_STATE_WTG_FOR_DESCENTRATE] = { .setup = &VtolLandFSM::setup_wtg_for_descentrate, .run = &VtolLandFSM::run_wtg_for_descentrate },
|
||||
[LAND_STATE_AT_DESCENTRATE] = { .setup = &VtolLandFSM::setup_at_descentrate, .run = &VtolLandFSM::run_at_descentrate },
|
||||
[LAND_STATE_WTG_FOR_GROUNDEFFECT] = { .setup = &VtolLandFSM::setup_wtg_for_groundeffect, .run = &VtolLandFSM::run_wtg_for_groundeffect },
|
||||
[LAND_STATE_GROUNDEFFECT] = { .setup = &VtolLandFSM::setup_groundeffect, .run = &VtolLandFSM::run_groundeffect },
|
||||
[LAND_STATE_THRUSTDOWN] = { .setup = &VtolLandFSM::setup_thrustdown, .run = &VtolLandFSM::run_thrustdown },
|
||||
[LAND_STATE_THRUSTOFF] = { .setup = &VtolLandFSM::setup_thrustoff, .run = &VtolLandFSM::run_thrustoff },
|
||||
[LAND_STATE_DISARMED] = { .setup = &VtolLandFSM::setup_disarmed, .run = &VtolLandFSM::run_disarmed },
|
||||
[LAND_STATE_ABORT] = { .setup = &VtolLandFSM::setup_abort, .run = &VtolLandFSM::run_abort }
|
||||
};
|
||||
|
||||
// pointer to a singleton instance
|
||||
VtolLandFSM *VtolLandFSM::p_inst = 0;
|
||||
|
||||
|
||||
VtolLandFSM::VtolLandFSM()
|
||||
: mLandData(0), vtolPathFollowerSettings(0), pathDesired(0), flightStatus(0)
|
||||
{}
|
||||
|
||||
// Private types
|
||||
|
||||
// Private functions
|
||||
// Public API methods
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t VtolLandFSM::Initialize(VtolPathFollowerSettingsData *ptr_vtolPathFollowerSettings,
|
||||
PathDesiredData *ptr_pathDesired,
|
||||
FlightStatusData *ptr_flightStatus)
|
||||
{
|
||||
PIOS_Assert(ptr_vtolPathFollowerSettings);
|
||||
PIOS_Assert(ptr_pathDesired);
|
||||
PIOS_Assert(ptr_flightStatus);
|
||||
|
||||
if (mLandData == 0) {
|
||||
mLandData = (VtolLandFSMData_T *)pios_malloc(sizeof(VtolLandFSMData_T));
|
||||
PIOS_Assert(mLandData);
|
||||
}
|
||||
memset(mLandData, 0, sizeof(VtolLandFSMData_T));
|
||||
vtolPathFollowerSettings = ptr_vtolPathFollowerSettings;
|
||||
pathDesired = ptr_pathDesired;
|
||||
flightStatus = ptr_flightStatus;
|
||||
initFSM();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void VtolLandFSM::Inactive(void)
|
||||
{
|
||||
memset(mLandData, 0, sizeof(VtolLandFSMData_T));
|
||||
initFSM();
|
||||
}
|
||||
|
||||
// Initialise the FSM
|
||||
void VtolLandFSM::initFSM(void)
|
||||
{
|
||||
if (vtolPathFollowerSettings != 0) {
|
||||
setState(STATUSVTOLLAND_STATE_INACTIVE, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
} else {
|
||||
mLandData->currentState = STATUSVTOLLAND_STATE_INACTIVE;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::Activate()
|
||||
{
|
||||
memset(mLandData, 0, sizeof(VtolLandFSMData_T));
|
||||
mLandData->currentState = STATUSVTOLLAND_STATE_INACTIVE;
|
||||
mLandData->flLowAltitude = false;
|
||||
mLandData->flAltitudeHold = false;
|
||||
mLandData->fsmLandStatus.averageDescentRate = MIN_LANDRATE;
|
||||
mLandData->fsmLandStatus.averageDescentThrust = vtolPathFollowerSettings->ThrustLimits.Neutral;
|
||||
mLandData->fsmLandStatus.calculatedNeutralThrust = vtolPathFollowerSettings->ThrustLimits.Neutral;
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
TakeOffLocationGet(&(mLandData->takeOffLocation));
|
||||
mLandData->fsmLandStatus.AltitudeAtState[STATUSVTOLLAND_STATE_INACTIVE] = 0.0f;
|
||||
assessAltitude();
|
||||
|
||||
if (pathDesired->Mode == PATHDESIRED_MODE_LAND) {
|
||||
#ifndef DEBUG_GROUNDIMPACT
|
||||
setState(STATUSVTOLLAND_STATE_INITALTHOLD, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
#else
|
||||
setState(STATUSVTOLLAND_STATE_WTGFORGROUNDEFFECT, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
#endif
|
||||
} else {
|
||||
// move to error state and callback to position hold
|
||||
setState(STATUSVTOLLAND_STATE_ABORT, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::Abort(void)
|
||||
{
|
||||
setState(STATUSVTOLLAND_STATE_ABORT, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
}
|
||||
|
||||
PathFollowerFSMState_T VtolLandFSM::GetCurrentState(void)
|
||||
{
|
||||
switch (mLandData->currentState) {
|
||||
case STATUSVTOLLAND_STATE_INACTIVE:
|
||||
return PFFSM_STATE_INACTIVE;
|
||||
|
||||
break;
|
||||
case STATUSVTOLLAND_STATE_ABORT:
|
||||
return PFFSM_STATE_ABORT;
|
||||
|
||||
break;
|
||||
case STATUSVTOLLAND_STATE_DISARMED:
|
||||
return PFFSM_STATE_DISARMED;
|
||||
|
||||
break;
|
||||
default:
|
||||
return PFFSM_STATE_ACTIVE;
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::Update()
|
||||
{
|
||||
runState();
|
||||
if (GetCurrentState() != PFFSM_STATE_INACTIVE) {
|
||||
runAlways();
|
||||
}
|
||||
}
|
||||
|
||||
int32_t VtolLandFSM::runState(void)
|
||||
{
|
||||
uint8_t flTimeout = false;
|
||||
|
||||
mLandData->stateRunCount++;
|
||||
|
||||
if (mLandData->stateTimeoutCount > 0 && mLandData->stateRunCount > mLandData->stateTimeoutCount) {
|
||||
flTimeout = true;
|
||||
}
|
||||
|
||||
// If the current state has a static function, call it
|
||||
if (sLandStateTable[mLandData->currentState].run) {
|
||||
(this->*sLandStateTable[mLandData->currentState].run)(flTimeout);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t VtolLandFSM::runAlways(void)
|
||||
{
|
||||
void assessAltitude(void);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
// PathFollower implements the PID scheme and has a objective
|
||||
// set by a PathDesired object. Based on the mode, pathfollower
|
||||
// uses FSM's as helper functions that manage state and event detection.
|
||||
// PathFollower calls into FSM methods to alter its commands.
|
||||
|
||||
void VtolLandFSM::BoundThrust(float &ulow, float &uhigh)
|
||||
{
|
||||
ulow = mLandData->boundThrustMin;
|
||||
uhigh = mLandData->boundThrustMax;
|
||||
|
||||
|
||||
if (mLandData->flConstrainThrust) {
|
||||
uhigh = mLandData->thrustLimit;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::ConstrainStabiDesired(StabilizationDesiredData *stabDesired)
|
||||
{
|
||||
if (mLandData->flZeroStabiHorizontal && stabDesired) {
|
||||
stabDesired->Pitch = 0.0f;
|
||||
stabDesired->Roll = 0.0f;
|
||||
stabDesired->Yaw = 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::CheckPidScaler(pid_scaler *local_scaler)
|
||||
{
|
||||
if (mLandData->flLowAltitude) {
|
||||
local_scaler->p = LANDING_PID_SCALAR_P;
|
||||
local_scaler->i = LANDING_PID_SCALAR_I;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Set the new state and perform setup for subsequent state run calls
|
||||
// This is called by state run functions on event detection that drive
|
||||
// state transitions.
|
||||
void VtolLandFSM::setState(StatusVtolLandStateOptions newState, StatusVtolLandStateExitReasonOptions reason)
|
||||
{
|
||||
mLandData->fsmLandStatus.StateExitReason[mLandData->currentState] = reason;
|
||||
|
||||
if (mLandData->currentState == newState) {
|
||||
return;
|
||||
}
|
||||
mLandData->currentState = newState;
|
||||
|
||||
if (newState != STATUSVTOLLAND_STATE_INACTIVE) {
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
float takeOffDown = 0.0f;
|
||||
if (mLandData->takeOffLocation.Status == TAKEOFFLOCATION_STATUS_VALID) {
|
||||
takeOffDown = mLandData->takeOffLocation.Down;
|
||||
}
|
||||
mLandData->fsmLandStatus.AltitudeAtState[newState] = positionState.Down - takeOffDown;
|
||||
assessAltitude();
|
||||
}
|
||||
|
||||
// Restart state timer counter
|
||||
mLandData->stateRunCount = 0;
|
||||
|
||||
// Reset state timeout to disabled/zero
|
||||
mLandData->stateTimeoutCount = 0;
|
||||
|
||||
if (sLandStateTable[mLandData->currentState].setup) {
|
||||
(this->*sLandStateTable[mLandData->currentState].setup)();
|
||||
}
|
||||
|
||||
updateVtolLandFSMStatus();
|
||||
}
|
||||
|
||||
|
||||
// Timeout utility function for use by state init implementations
|
||||
void VtolLandFSM::setStateTimeout(int32_t count)
|
||||
{
|
||||
mLandData->stateTimeoutCount = count;
|
||||
}
|
||||
|
||||
void VtolLandFSM::updateVtolLandFSMStatus()
|
||||
{
|
||||
mLandData->fsmLandStatus.State = mLandData->currentState;
|
||||
if (mLandData->flLowAltitude) {
|
||||
mLandData->fsmLandStatus.AltitudeState = STATUSVTOLLAND_ALTITUDESTATE_LOW;
|
||||
} else {
|
||||
mLandData->fsmLandStatus.AltitudeState = STATUSVTOLLAND_ALTITUDESTATE_HIGH;
|
||||
}
|
||||
StatusVtolLandSet(&mLandData->fsmLandStatus);
|
||||
}
|
||||
|
||||
|
||||
float VtolLandFSM::BoundVelocityDown(float velocity_down)
|
||||
{
|
||||
velocity_down = boundf(velocity_down, MIN_LANDRATE, MAX_LANDRATE);
|
||||
if (mLandData->flLowAltitude) {
|
||||
velocity_down *= LOW_ALT_DESCENT_REDUCTION_FACTOR;
|
||||
}
|
||||
mLandData->fsmLandStatus.targetDescentRate = velocity_down;
|
||||
|
||||
if (mLandData->flAltitudeHold) {
|
||||
return 0.0f;
|
||||
} else {
|
||||
return velocity_down;
|
||||
}
|
||||
}
|
||||
|
||||
void VtolLandFSM::assessAltitude(void)
|
||||
{
|
||||
float positionDown;
|
||||
|
||||
PositionStateDownGet(&positionDown);
|
||||
float takeOffDown = 0.0f;
|
||||
if (mLandData->takeOffLocation.Status == TAKEOFFLOCATION_STATUS_VALID) {
|
||||
takeOffDown = mLandData->takeOffLocation.Down;
|
||||
}
|
||||
float positionDownRelativeToTakeoff = positionDown - takeOffDown;
|
||||
if (positionDownRelativeToTakeoff < LANDING_SLOWDOWN_HEIGHT) {
|
||||
mLandData->flLowAltitude = false;
|
||||
} else {
|
||||
mLandData->flLowAltitude = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// FSM Setup and Run method implementation
|
||||
|
||||
// State: INACTIVE
|
||||
void VtolLandFSM::setup_inactive(void)
|
||||
{
|
||||
// Re-initialise local variables
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->flConstrainThrust = false;
|
||||
}
|
||||
|
||||
// State: INIT ALTHOLD
|
||||
void VtolLandFSM::setup_init_althold(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_INIT_ALTHOLD);
|
||||
// get target descent velocity
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->fsmLandStatus.targetDescentRate = BoundVelocityDown(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_VELOCITYVECTOR_DOWN]);
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->flAltitudeHold = true;
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_init_althold(uint8_t flTimeout)
|
||||
{
|
||||
if (flTimeout) {
|
||||
mLandData->flAltitudeHold = false;
|
||||
setState(STATUSVTOLLAND_STATE_WTGFORDESCENTRATE, STATUSVTOLLAND_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// State: WAITING FOR DESCENT RATE
|
||||
void VtolLandFSM::setup_wtg_for_descentrate(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_WTG_FOR_DESCENTRATE);
|
||||
// get target descent velocity
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->observationCount = 0;
|
||||
mLandData->observation2Count = 0;
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->flAltitudeHold = false;
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_wtg_for_descentrate(uint8_t flTimeout)
|
||||
{
|
||||
// Look at current actual thrust...are we already shutdown??
|
||||
VelocityStateData velocityState;
|
||||
|
||||
VelocityStateGet(&velocityState);
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
|
||||
// We don't expect PID to get exactly the target descent rate, so have a lower
|
||||
// water mark but need to see 5 observations to be confident that we have semi-stable
|
||||
// descent achieved
|
||||
|
||||
// we need to see velocity down within a range of control before we proceed, without which we
|
||||
// really don't have confidence to allow later states to run.
|
||||
if (velocityState.Down > (LANDRATE_LOWLIMIT_FACTOR * mLandData->fsmLandStatus.targetDescentRate) &&
|
||||
velocityState.Down < (LANDRATE_HILIMIT_FACTOR * mLandData->fsmLandStatus.targetDescentRate)) {
|
||||
if (mLandData->observationCount++ > WTG_FOR_DESCENTRATE_COUNT_LIMIT) {
|
||||
setState(STATUSVTOLLAND_STATE_ATDESCENTRATE, STATUSVTOLLAND_STATEEXITREASON_DESCENTRATEOK);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
if (flTimeout) {
|
||||
setState(STATUSVTOLLAND_STATE_ABORT, STATUSVTOLLAND_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// State: AT DESCENT RATE
|
||||
void VtolLandFSM::setup_at_descentrate(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_AT_DESCENTRATE);
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->observationCount = 0;
|
||||
mLandData->sum1 = 0.0f;
|
||||
mLandData->sum2 = 0.0f;
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->fsmLandStatus.averageDescentRate = MIN_LANDRATE;
|
||||
mLandData->fsmLandStatus.averageDescentThrust = vtolPathFollowerSettings->ThrustLimits.Neutral;
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_at_descentrate(uint8_t flTimeout)
|
||||
{
|
||||
VelocityStateData velocityState;
|
||||
|
||||
VelocityStateGet(&velocityState);
|
||||
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
|
||||
mLandData->sum1 += velocityState.Down;
|
||||
mLandData->sum2 += stabDesired.Thrust;
|
||||
mLandData->observationCount++;
|
||||
if (flTimeout) {
|
||||
mLandData->fsmLandStatus.averageDescentRate = boundf((mLandData->sum1 / (float)(mLandData->observationCount)), 0.5f * MIN_LANDRATE, 1.5f * MAX_LANDRATE);
|
||||
mLandData->fsmLandStatus.averageDescentThrust = boundf((mLandData->sum2 / (float)(mLandData->observationCount)), vtolPathFollowerSettings->ThrustLimits.Min, vtolPathFollowerSettings->ThrustLimits.Max);
|
||||
|
||||
// We need to calculate a neutral limit to use later to constrain upper thrust range during states where we are close to the ground
|
||||
// As our battery gets flat, ThrustLimits.Neutral needs to constrain us too much and we get too fast a descent rate. We can
|
||||
// detect this by the fact that the descent rate will exceed the target and the required thrust will exceed the neutral value
|
||||
mLandData->fsmLandStatus.calculatedNeutralThrust = mLandData->fsmLandStatus.averageDescentRate / mLandData->fsmLandStatus.targetDescentRate * mLandData->fsmLandStatus.averageDescentThrust;
|
||||
mLandData->fsmLandStatus.calculatedNeutralThrust = boundf(mLandData->fsmLandStatus.calculatedNeutralThrust, vtolPathFollowerSettings->ThrustLimits.Neutral, vtolPathFollowerSettings->ThrustLimits.Max);
|
||||
|
||||
|
||||
setState(STATUSVTOLLAND_STATE_WTGFORGROUNDEFFECT, STATUSVTOLLAND_STATEEXITREASON_DESCENTRATEOK);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// State: WAITING FOR GROUND EFFECT
|
||||
void VtolLandFSM::setup_wtg_for_groundeffect(void)
|
||||
{
|
||||
// No timeout
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->observationCount = 0;
|
||||
mLandData->observation2Count = 0;
|
||||
mLandData->sum1 = 0.0f;
|
||||
mLandData->sum2 = 0.0f;
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceVelocity = 0.0f;
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceAccel = 0.0f;
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_wtg_for_groundeffect(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
// detect material downrating in thrust for 1 second.
|
||||
VelocityStateData velocityState;
|
||||
|
||||
VelocityStateGet(&velocityState);
|
||||
AccelStateData accelState;
|
||||
AccelStateGet(&accelState);
|
||||
|
||||
// +ve 9.8 expected
|
||||
float g_e;
|
||||
HomeLocationg_eGet(&g_e);
|
||||
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
|
||||
// detect bounce
|
||||
uint8_t flBounce = (velocityState.Down < BOUNCE_VELOCITY_TRIGGER_LIMIT);
|
||||
if (flBounce) {
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceVelocity = velocityState.Down;
|
||||
} else {
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceVelocity = 0.0f;
|
||||
}
|
||||
|
||||
// invert sign of accel to the standard convention of down is +ve and subtract the gravity to get
|
||||
// a relative acceleration term.
|
||||
float bounceAccel = -accelState.z - g_e;
|
||||
uint8_t flBounceAccel = (bounceAccel < BOUNCE_ACCELERATION_TRIGGER_LIMIT);
|
||||
if (flBounceAccel) {
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceAccel = bounceAccel;
|
||||
} else {
|
||||
mLandData->fsmLandStatus.WtgForGroundEffect.BounceAccel = 0.0f;
|
||||
}
|
||||
|
||||
if (flBounce) { // || flBounceAccel) { // accel trigger can occur due to vibration and is too sensitive
|
||||
mLandData->observation2Count++;
|
||||
if (mLandData->observation2Count > BOUNCE_TRIGGER_COUNT) {
|
||||
setState(STATUSVTOLLAND_STATE_GROUNDEFFECT, (flBounce ? STATUSVTOLLAND_STATEEXITREASON_BOUNCEVELOCITY : STATUSVTOLLAND_STATEEXITREASON_BOUNCEACCEL));
|
||||
return;
|
||||
}
|
||||
} else {
|
||||
mLandData->observation2Count = 0;
|
||||
}
|
||||
|
||||
// detect low descent rate
|
||||
uint8_t flDescentRateLow = (velocityState.Down < (GROUNDEFFECT_SLOWDOWN_FACTOR * mLandData->fsmLandStatus.averageDescentRate));
|
||||
if (flDescentRateLow) {
|
||||
mLandData->boundThrustMax = mLandData->fsmLandStatus.calculatedNeutralThrust;
|
||||
mLandData->observationCount++;
|
||||
if (mLandData->observationCount > GROUNDEFFECT_SLOWDOWN_COUNT) {
|
||||
#ifndef DEBUG_GROUNDIMPACT
|
||||
setState(STATUSVTOLLAND_STATE_GROUNDEFFECT, STATUSVTOLLAND_STATEEXITREASON_LOWDESCENTRATE);
|
||||
#endif
|
||||
return;
|
||||
}
|
||||
} else {
|
||||
mLandData->observationCount = 0;
|
||||
}
|
||||
|
||||
updateVtolLandFSMStatus();
|
||||
}
|
||||
|
||||
// STATE: GROUNDEFFET
|
||||
void VtolLandFSM::setup_groundeffect(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_GROUNDEFFECT);
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
mLandData->expectedLandPositionNorth = positionState.North;
|
||||
mLandData->expectedLandPositionEast = positionState.East;
|
||||
mLandData->flConstrainThrust = false;
|
||||
|
||||
// now that we have ground effect limit max thrust to neutral
|
||||
mLandData->boundThrustMin = -0.1f;
|
||||
mLandData->boundThrustMax = mLandData->fsmLandStatus.calculatedNeutralThrust;
|
||||
}
|
||||
void VtolLandFSM::run_groundeffect(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
StabilizationDesiredData stabDesired;
|
||||
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
if (stabDesired.Thrust < 0.0f) {
|
||||
setState(STATUSVTOLLAND_STATE_THRUSTOFF, STATUSVTOLLAND_STATEEXITREASON_ZEROTHRUST);
|
||||
return;
|
||||
}
|
||||
|
||||
// Stay in this state until we get a low altitude flag.
|
||||
if (mLandData->flLowAltitude == false) {
|
||||
// worst case scenario is that we land and the pid brings thrust down to zero.
|
||||
return;
|
||||
}
|
||||
|
||||
// detect broad sideways drift. If for some reason we have a hard landing that the bounce detection misses, this will kick in
|
||||
PositionStateData positionState;
|
||||
PositionStateGet(&positionState);
|
||||
float north_error = mLandData->expectedLandPositionNorth - positionState.North;
|
||||
float east_error = mLandData->expectedLandPositionEast - positionState.East;
|
||||
float positionError = sqrtf(north_error * north_error + east_error * east_error);
|
||||
if (positionError > 1.5f) {
|
||||
setState(STATUSVTOLLAND_STATE_THRUSTDOWN, STATUSVTOLLAND_STATEEXITREASON_POSITIONERROR);
|
||||
return;
|
||||
}
|
||||
|
||||
if (flTimeout) {
|
||||
setState(STATUSVTOLLAND_STATE_THRUSTDOWN, STATUSVTOLLAND_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
// STATE: THRUSTDOWN
|
||||
void VtolLandFSM::setup_thrustdown(void)
|
||||
{
|
||||
setStateTimeout(TIMEOUT_THRUSTDOWN);
|
||||
mLandData->flZeroStabiHorizontal = true;
|
||||
mLandData->flConstrainThrust = true;
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
mLandData->thrustLimit = stabDesired.Thrust;
|
||||
mLandData->sum1 = stabDesired.Thrust / (float)TIMEOUT_THRUSTDOWN;
|
||||
mLandData->boundThrustMin = -0.1f;
|
||||
mLandData->boundThrustMax = mLandData->fsmLandStatus.calculatedNeutralThrust;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_thrustdown(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
// reduce thrust setpoint step by step
|
||||
mLandData->thrustLimit -= mLandData->sum1;
|
||||
|
||||
StabilizationDesiredData stabDesired;
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
if (stabDesired.Thrust < 0.0f || mLandData->thrustLimit < 0.0f) {
|
||||
setState(STATUSVTOLLAND_STATE_THRUSTOFF, STATUSVTOLLAND_STATEEXITREASON_ZEROTHRUST);
|
||||
}
|
||||
|
||||
if (flTimeout) {
|
||||
setState(STATUSVTOLLAND_STATE_THRUSTOFF, STATUSVTOLLAND_STATEEXITREASON_TIMEOUT);
|
||||
}
|
||||
}
|
||||
|
||||
// STATE: THRUSTOFF
|
||||
void VtolLandFSM::setup_thrustoff(void)
|
||||
{
|
||||
mLandData->thrustLimit = -1.0f;
|
||||
mLandData->flConstrainThrust = true;
|
||||
mLandData->boundThrustMin = -0.1f;
|
||||
mLandData->boundThrustMax = 0.0f;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_thrustoff(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
setState(STATUSVTOLLAND_STATE_DISARMED, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
}
|
||||
|
||||
// STATE: DISARMED
|
||||
void VtolLandFSM::setup_disarmed(void)
|
||||
{
|
||||
// nothing to do
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
mLandData->observationCount = 0;
|
||||
mLandData->boundThrustMin = -0.1f;
|
||||
mLandData->boundThrustMax = 0.0f;
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_disarmed(__attribute__((unused)) uint8_t flTimeout)
|
||||
{
|
||||
#ifdef DEBUG_GROUNDIMPACT
|
||||
if (mLandData->observationCount++ > 100) {
|
||||
setState(STATUSVTOLLAND_STATE_WTGFORGROUNDEFFECT, STATUSVTOLLAND_STATEEXITREASON_NONE);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void VtolLandFSM::fallback_to_hold(void)
|
||||
{
|
||||
PositionStateData positionState;
|
||||
|
||||
PositionStateGet(&positionState);
|
||||
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_GOTOENDPOINT;
|
||||
|
||||
PathDesiredSet(pathDesired);
|
||||
}
|
||||
|
||||
// abort repeatedly overwrites pathfollower's objective on a landing abort and
|
||||
// continues to do so until a flight mode change.
|
||||
void VtolLandFSM::setup_abort(void)
|
||||
{
|
||||
mLandData->boundThrustMin = vtolPathFollowerSettings->ThrustLimits.Min;
|
||||
mLandData->boundThrustMax = vtolPathFollowerSettings->ThrustLimits.Max;
|
||||
mLandData->flConstrainThrust = false;
|
||||
mLandData->flZeroStabiHorizontal = false;
|
||||
fallback_to_hold();
|
||||
}
|
||||
|
||||
void VtolLandFSM::run_abort(__attribute__((unused)) uint8_t flTimeout)
|
||||
{}
|
||||
|
@ -48,6 +48,9 @@
|
||||
#include "plans.h"
|
||||
#include <sanitycheck.h>
|
||||
#include <vtolpathfollowersettings.h>
|
||||
#include <statusvtolautotakeoff.h>
|
||||
#include <statusvtolland.h>
|
||||
#include <manualcontrolcommand.h>
|
||||
|
||||
// Private constants
|
||||
#define STACK_SIZE_BYTES 1024
|
||||
@ -77,6 +80,9 @@ static uint8_t conditionPointingTowardsNext();
|
||||
static uint8_t conditionPythonScript();
|
||||
static uint8_t conditionImmediate();
|
||||
static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev);
|
||||
static void planner_setup_pathdesired_land(PathDesiredData *pathDesired);
|
||||
static void planner_setup_pathdesired_takeoff(PathDesiredData *pathDesired);
|
||||
static void planner_setup_pathdesired(PathDesiredData *pathDesired);
|
||||
|
||||
|
||||
// Private variables
|
||||
@ -126,6 +132,8 @@ int32_t PathPlannerInitialize()
|
||||
VelocityStateInitialize();
|
||||
WaypointInitialize();
|
||||
WaypointActiveInitialize();
|
||||
StatusVtolAutoTakeoffInitialize();
|
||||
StatusVtolLandInitialize();
|
||||
|
||||
pathPlannerHandle = PIOS_CALLBACKSCHEDULER_Create(&pathPlannerTask, CALLBACK_PRIORITY_REGULAR, TASK_PRIORITY, CALLBACKINFO_RUNNING_PATHPLANNER0, STACK_SIZE_BYTES);
|
||||
pathDesiredUpdaterHandle = PIOS_CALLBACKSCHEDULER_Create(&updatePathDesired, CALLBACK_PRIORITY_CRITICAL, TASK_PRIORITY, CALLBACKINFO_RUNNING_PATHPLANNER1, STACK_SIZE_BYTES);
|
||||
@ -138,7 +146,7 @@ MODULE_INITCALL(PathPlannerInitialize, PathPlannerStart);
|
||||
|
||||
static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
uint8_t TreatCustomCraftAs;
|
||||
VtolPathFollowerSettingsTreatCustomCraftAsOptions TreatCustomCraftAs;
|
||||
|
||||
VtolPathFollowerSettingsTreatCustomCraftAsGet(&TreatCustomCraftAs);
|
||||
|
||||
@ -167,6 +175,7 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
}
|
||||
}
|
||||
|
||||
#define AUTOTAKEOFF_THROTTLE_LIMIT_TO_ALLOW_TAKEOFF_START 0.3f
|
||||
|
||||
/**
|
||||
* Module task
|
||||
@ -219,6 +228,17 @@ static void pathPlannerTask()
|
||||
|
||||
WaypointActiveGet(&waypointActive);
|
||||
|
||||
// with the introduction of takeoff, we allow for arming
|
||||
// whilst in pathplanner mode. Previously it was just an assumption that
|
||||
// a user never armed in pathplanner mode. This check allows a user to select
|
||||
// pathplanner, to upload waypoints, and then arm in pathplanner.
|
||||
if (!flightStatus.Armed) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
// the transition from pathplanner to another flightmode back to pathplanner
|
||||
// triggers a reset back to 0 index in the waypoint list
|
||||
if (pathplanner_active == false) {
|
||||
pathplanner_active = true;
|
||||
|
||||
@ -245,6 +265,22 @@ static void pathPlannerTask()
|
||||
return;
|
||||
}
|
||||
|
||||
// check start conditions
|
||||
// autotakeoff requires midpoint thrust if we are in a pending takeoff situation
|
||||
if (pathAction.Mode == PATHACTION_MODE_AUTOTAKEOFF) {
|
||||
pathAction.EndCondition = PATHACTION_ENDCONDITION_LEGREMAINING;
|
||||
if ((uint8_t)pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE] == STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE) {
|
||||
ManualControlCommandData cmd;
|
||||
ManualControlCommandGet(&cmd);
|
||||
if (cmd.Throttle > AUTOTAKEOFF_THROTTLE_LIMIT_TO_ALLOW_TAKEOFF_START) {
|
||||
pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE] = (float)STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_INITIATE;
|
||||
PathDesiredSet(&pathDesired);
|
||||
}
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// check if condition has been met
|
||||
endCondition = pathConditionCheck();
|
||||
// decide what to do
|
||||
@ -283,6 +319,38 @@ static void pathPlannerTask()
|
||||
}
|
||||
}
|
||||
|
||||
// callback function when waypoints changed in any way, update pathDesired
|
||||
void updatePathDesired()
|
||||
{
|
||||
// only ever touch pathDesired if pathplanner is enabled
|
||||
if (!pathplanner_active) {
|
||||
return;
|
||||
}
|
||||
|
||||
PathDesiredData pathDesired;
|
||||
|
||||
// find out current waypoint
|
||||
WaypointActiveGet(&waypointActive);
|
||||
|
||||
WaypointInstGet(waypointActive.Index, &waypoint);
|
||||
PathActionInstGet(waypoint.Action, &pathAction);
|
||||
|
||||
switch (pathAction.Mode) {
|
||||
case PATHACTION_MODE_AUTOTAKEOFF:
|
||||
planner_setup_pathdesired_takeoff(&pathDesired);
|
||||
break;
|
||||
case PATHACTION_MODE_LAND:
|
||||
planner_setup_pathdesired_land(&pathDesired);
|
||||
break;
|
||||
default:
|
||||
planner_setup_pathdesired(&pathDesired);
|
||||
break;
|
||||
}
|
||||
|
||||
PathDesiredSet(&pathDesired);
|
||||
}
|
||||
|
||||
|
||||
// safety checks for path plan integrity
|
||||
static uint8_t checkPathPlan()
|
||||
{
|
||||
@ -367,33 +435,20 @@ void statusUpdated(__attribute__((unused)) UAVObjEvent *ev)
|
||||
PIOS_CALLBACKSCHEDULER_Dispatch(pathPlannerHandle);
|
||||
}
|
||||
|
||||
|
||||
// callback function when waypoints changed in any way, update pathDesired
|
||||
void updatePathDesired()
|
||||
// Standard setup of a pathDesired command from the waypoint path plan
|
||||
static void planner_setup_pathdesired(PathDesiredData *pathDesired)
|
||||
{
|
||||
// only ever touch pathDesired if pathplanner is enabled
|
||||
if (!pathplanner_active) {
|
||||
return;
|
||||
}
|
||||
pathDesired->End.North = waypoint.Position.North;
|
||||
pathDesired->End.East = waypoint.Position.East;
|
||||
pathDesired->End.Down = waypoint.Position.Down;
|
||||
pathDesired->EndingVelocity = waypoint.Velocity;
|
||||
pathDesired->Mode = pathAction.Mode;
|
||||
pathDesired->ModeParameters[0] = pathAction.ModeParameters[0];
|
||||
pathDesired->ModeParameters[1] = pathAction.ModeParameters[1];
|
||||
pathDesired->ModeParameters[2] = pathAction.ModeParameters[2];
|
||||
pathDesired->ModeParameters[3] = pathAction.ModeParameters[3];
|
||||
pathDesired->UID = waypointActive.Index;
|
||||
|
||||
PathDesiredData pathDesired;
|
||||
|
||||
// find out current waypoint
|
||||
WaypointActiveGet(&waypointActive);
|
||||
|
||||
WaypointInstGet(waypointActive.Index, &waypoint);
|
||||
PathActionInstGet(waypoint.Action, &pathAction);
|
||||
|
||||
pathDesired.End.North = waypoint.Position.North;
|
||||
pathDesired.End.East = waypoint.Position.East;
|
||||
pathDesired.End.Down = waypoint.Position.Down;
|
||||
pathDesired.EndingVelocity = waypoint.Velocity;
|
||||
pathDesired.Mode = pathAction.Mode;
|
||||
pathDesired.ModeParameters[0] = pathAction.ModeParameters[0];
|
||||
pathDesired.ModeParameters[1] = pathAction.ModeParameters[1];
|
||||
pathDesired.ModeParameters[2] = pathAction.ModeParameters[2];
|
||||
pathDesired.ModeParameters[3] = pathAction.ModeParameters[3];
|
||||
pathDesired.UID = waypointActive.Index;
|
||||
|
||||
if (waypointActive.Index == 0) {
|
||||
PositionStateData positionState;
|
||||
@ -403,23 +458,90 @@ void updatePathDesired()
|
||||
/*pathDesired.Start[PATHDESIRED_START_NORTH] = waypoint.Position[WAYPOINT_POSITION_NORTH];
|
||||
pathDesired.Start[PATHDESIRED_START_EAST] = waypoint.Position[WAYPOINT_POSITION_EAST];
|
||||
pathDesired.Start[PATHDESIRED_START_DOWN] = waypoint.Position[WAYPOINT_POSITION_DOWN];*/
|
||||
pathDesired.Start.North = positionState.North;
|
||||
pathDesired.Start.East = positionState.East;
|
||||
pathDesired.Start.Down = positionState.Down;
|
||||
pathDesired.StartingVelocity = pathDesired.EndingVelocity;
|
||||
// note takeoff relies on the start being the current location as it merely ascends and using
|
||||
// the start as assumption current NE location
|
||||
pathDesired->Start.North = positionState.North;
|
||||
pathDesired->Start.East = positionState.East;
|
||||
pathDesired->Start.Down = positionState.Down;
|
||||
pathDesired->StartingVelocity = pathDesired->EndingVelocity;
|
||||
} else {
|
||||
// Get previous waypoint as start point
|
||||
WaypointData waypointPrev;
|
||||
WaypointInstGet(waypointActive.Index - 1, &waypointPrev);
|
||||
|
||||
pathDesired.Start.North = waypointPrev.Position.North;
|
||||
pathDesired.Start.East = waypointPrev.Position.East;
|
||||
pathDesired.Start.Down = waypointPrev.Position.Down;
|
||||
pathDesired.StartingVelocity = waypointPrev.Velocity;
|
||||
pathDesired->Start.North = waypointPrev.Position.North;
|
||||
pathDesired->Start.East = waypointPrev.Position.East;
|
||||
pathDesired->Start.Down = waypointPrev.Position.Down;
|
||||
pathDesired->StartingVelocity = waypointPrev.Velocity;
|
||||
}
|
||||
PathDesiredSet(&pathDesired);
|
||||
}
|
||||
|
||||
#define AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN 2.0f
|
||||
#define AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX 50.0f
|
||||
static void planner_setup_pathdesired_takeoff(PathDesiredData *pathDesired)
|
||||
{
|
||||
PositionStateData positionState;
|
||||
|
||||
PositionStateGet(&positionState);
|
||||
float velocity_down;
|
||||
float autotakeoff_height;
|
||||
FlightModeSettingsAutoTakeOffVelocityGet(&velocity_down);
|
||||
FlightModeSettingsAutoTakeOffHeightGet(&autotakeoff_height);
|
||||
autotakeoff_height = fabsf(autotakeoff_height);
|
||||
if (autotakeoff_height < AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN) {
|
||||
autotakeoff_height = AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN;
|
||||
} else if (autotakeoff_height > AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX) {
|
||||
autotakeoff_height = AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX;
|
||||
}
|
||||
|
||||
|
||||
pathDesired->Start.North = positionState.North;
|
||||
pathDesired->Start.East = positionState.East;
|
||||
pathDesired->Start.Down = positionState.Down;
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_NORTH] = 0.0f;
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_EAST] = 0.0f;
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_DOWN] = -velocity_down;
|
||||
// initially halt takeoff.
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE] = (float)STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE;
|
||||
|
||||
pathDesired->End.North = positionState.North;
|
||||
pathDesired->End.East = positionState.East;
|
||||
pathDesired->End.Down = positionState.Down - autotakeoff_height;
|
||||
|
||||
pathDesired->StartingVelocity = 0.0f;
|
||||
pathDesired->EndingVelocity = 0.0f;
|
||||
pathDesired->Mode = PATHDESIRED_MODE_AUTOTAKEOFF;
|
||||
|
||||
pathDesired->UID = waypointActive.Index;
|
||||
}
|
||||
|
||||
static void planner_setup_pathdesired_land(PathDesiredData *pathDesired)
|
||||
{
|
||||
PositionStateData positionState;
|
||||
|
||||
PositionStateGet(&positionState);
|
||||
float velocity_down;
|
||||
|
||||
FlightModeSettingsLandingVelocityGet(&velocity_down);
|
||||
|
||||
pathDesired->Start.North = positionState.North;
|
||||
pathDesired->Start.East = positionState.East;
|
||||
pathDesired->Start.Down = positionState.Down;
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_VELOCITYVECTOR_NORTH] = 0.0f;
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_VELOCITYVECTOR_EAST] = 0.0f;
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_VELOCITYVECTOR_DOWN] = velocity_down;
|
||||
|
||||
pathDesired->End.North = positionState.North;
|
||||
pathDesired->End.East = positionState.East;
|
||||
pathDesired->End.Down = positionState.Down;
|
||||
|
||||
pathDesired->StartingVelocity = 0.0f;
|
||||
pathDesired->EndingVelocity = 0.0f;
|
||||
pathDesired->Mode = PATHDESIRED_MODE_LAND;
|
||||
pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_OPTIONS] = (float)PATHDESIRED_MODEPARAMETER_LAND_OPTION_HORIZONTAL_PH;
|
||||
}
|
||||
|
||||
|
||||
// helper function to go to a specific waypoint
|
||||
static void setWaypoint(uint16_t num)
|
||||
{
|
||||
@ -553,18 +675,11 @@ static uint8_t conditionDistanceToTarget()
|
||||
*/
|
||||
static uint8_t conditionLegRemaining()
|
||||
{
|
||||
PathDesiredData pathDesired;
|
||||
PositionStateData positionState;
|
||||
PathStatusData pathStatus;
|
||||
|
||||
PathDesiredGet(&pathDesired);
|
||||
PositionStateGet(&positionState);
|
||||
PathStatusGet(&pathStatus);
|
||||
|
||||
float cur[3] = { positionState.North, positionState.East, positionState.Down };
|
||||
struct path_status progress;
|
||||
|
||||
path_progress(&pathDesired,
|
||||
cur, &progress, mode3D);
|
||||
if (progress.fractional_progress >= 1.0f - pathAction.ConditionParameters[0]) {
|
||||
if (pathStatus.fractional_progress >= (1.0f - pathAction.ConditionParameters[0])) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
@ -612,6 +612,9 @@ static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_SBUS;
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_SRXL;
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_GCS;
|
||||
break;
|
||||
|
@ -444,8 +444,8 @@ static void handleGyro(float *samples, float temperature)
|
||||
static void handleMag(float *samples, float temperature)
|
||||
{
|
||||
MagSensorData mag;
|
||||
float mags[3] = { (float)samples[1] - mag_bias[0],
|
||||
(float)samples[0] - mag_bias[1],
|
||||
float mags[3] = { (float)samples[0] - mag_bias[0],
|
||||
(float)samples[1] - mag_bias[1],
|
||||
(float)samples[2] - mag_bias[2] };
|
||||
|
||||
rot_mult(mag_transform, mags, samples);
|
||||
|
@ -49,7 +49,7 @@
|
||||
#include <stabilization.h>
|
||||
#include <virtualflybar.h>
|
||||
#include <cruisecontrol.h>
|
||||
|
||||
#include <sanitycheck.h>
|
||||
// Private constants
|
||||
|
||||
#define CALLBACK_PRIORITY CALLBACK_PRIORITY_CRITICAL
|
||||
@ -66,6 +66,7 @@ static float axis_lock_accum[3] = { 0, 0, 0 };
|
||||
static uint8_t previous_mode[AXES] = { 255, 255, 255, 255 };
|
||||
static PiOSDeltatimeConfig timeval;
|
||||
static float speedScaleFactor = 1.0f;
|
||||
static bool frame_is_multirotor;
|
||||
|
||||
// Private functions
|
||||
static void stabilizationInnerloopTask();
|
||||
@ -95,6 +96,8 @@ void stabilizationInnerloopInit()
|
||||
|
||||
// schedule dead calls every FAILSAFE_TIMEOUT_MS to have the watchdog cleared
|
||||
PIOS_CALLBACKSCHEDULER_Schedule(callbackHandle, FAILSAFE_TIMEOUT_MS, CALLBACK_UPDATEMODE_LATER);
|
||||
|
||||
frame_is_multirotor = (GetCurrentFrameType() == FRAME_TYPE_MULTIROTOR);
|
||||
}
|
||||
|
||||
static float get_pid_scale_source_value()
|
||||
@ -241,6 +244,10 @@ static void stabilizationInnerloopTask()
|
||||
float dT;
|
||||
dT = PIOS_DELTATIME_GetAverageSeconds(&timeval);
|
||||
|
||||
StabilizationStatusOuterLoopData outerLoop;
|
||||
StabilizationStatusOuterLoopGet(&outerLoop);
|
||||
bool allowPiroComp = true;
|
||||
|
||||
for (t = 0; t < AXES; t++) {
|
||||
bool reinit = (StabilizationStatusInnerLoopToArray(enabled)[t] != previous_mode[t]);
|
||||
previous_mode[t] = StabilizationStatusInnerLoopToArray(enabled)[t];
|
||||
@ -248,6 +255,15 @@ static void stabilizationInnerloopTask()
|
||||
if (t < STABILIZATIONSTATUS_INNERLOOP_THRUST) {
|
||||
if (reinit) {
|
||||
stabSettings.innerPids[t].iAccumulator = 0;
|
||||
if (frame_is_multirotor) {
|
||||
// Multirotors should dump axis lock accumulators when unarmed or throttle is low.
|
||||
// Fixed wing or ground vehicles can fly/drive with low throttle.
|
||||
axis_lock_accum[t] = 0;
|
||||
}
|
||||
}
|
||||
// Any self leveling on roll or pitch must prevent pirouette compensation
|
||||
if (t < STABILIZATIONSTATUS_INNERLOOP_YAW && StabilizationStatusOuterLoopToArray(outerLoop)[t] != STABILIZATIONSTATUS_OUTERLOOP_DIRECT) {
|
||||
allowPiroComp = false;
|
||||
}
|
||||
switch (StabilizationStatusInnerLoopToArray(enabled)[t]) {
|
||||
case STABILIZATIONSTATUS_INNERLOOP_VIRTUALFLYBAR:
|
||||
@ -322,7 +338,7 @@ static void stabilizationInnerloopTask()
|
||||
}
|
||||
}
|
||||
|
||||
if (stabSettings.stabBank.EnablePiroComp == STABILIZATIONBANK_ENABLEPIROCOMP_TRUE && stabSettings.innerPids[0].iLim > 1e-3f && stabSettings.innerPids[1].iLim > 1e-3f) {
|
||||
if (allowPiroComp && stabSettings.stabBank.EnablePiroComp == STABILIZATIONBANK_ENABLEPIROCOMP_TRUE && stabSettings.innerPids[0].iLim > 1e-3f && stabSettings.innerPids[1].iLim > 1e-3f) {
|
||||
// attempted piro compensation - rotate pitch and yaw integrals (experimental)
|
||||
float angleYaw = DEG2RAD(gyro_filtered[2] * dT);
|
||||
float sinYaw = sinf(angleYaw);
|
||||
@ -334,7 +350,7 @@ static void stabilizationInnerloopTask()
|
||||
}
|
||||
|
||||
{
|
||||
uint8_t armed;
|
||||
FlightStatusArmedOptions armed;
|
||||
FlightStatusArmedGet(&armed);
|
||||
float throttleDesired;
|
||||
ManualControlCommandThrottleGet(&throttleDesired);
|
||||
|
@ -120,6 +120,7 @@ static void stabilizationOuterloopTask()
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_WEAKLEVELING:
|
||||
rpy_desired[t] = stabilizationDesiredAxis[t];
|
||||
break;
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_DIRECTWITHLIMITS:
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_DIRECT:
|
||||
default:
|
||||
rpy_desired[t] = ((float *)&attitudeState.Roll)[t];
|
||||
@ -148,6 +149,8 @@ static void stabilizationOuterloopTask()
|
||||
}
|
||||
#endif /* if defined(PIOS_QUATERNION_STABILIZATION) */
|
||||
}
|
||||
|
||||
|
||||
for (t = 0; t < AXES; t++) {
|
||||
bool reinit = (StabilizationStatusOuterLoopToArray(enabled)[t] != previous_mode[t]);
|
||||
previous_mode[t] = StabilizationStatusOuterLoopToArray(enabled)[t];
|
||||
@ -239,6 +242,40 @@ static void stabilizationOuterloopTask()
|
||||
rateDesiredAxis[t] = rate_input + weak_leveling;
|
||||
}
|
||||
break;
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_DIRECTWITHLIMITS:
|
||||
rateDesiredAxis[t] = stabilizationDesiredAxis[t]; // default for all axes
|
||||
// now test limits for pitch and/or roll
|
||||
if (t == 1) { // pitch
|
||||
if (attitudeState.Pitch < -stabSettings.stabBank.PitchMax) {
|
||||
// attitude exceeds pitch max.
|
||||
// zero rate desired if also -ve
|
||||
if (rateDesiredAxis[t] < 0.0f) {
|
||||
rateDesiredAxis[t] = 0.0f;
|
||||
}
|
||||
} else if (attitudeState.Pitch > stabSettings.stabBank.PitchMax) {
|
||||
// attitude exceeds pitch max
|
||||
// zero rate desired if also +ve
|
||||
if (rateDesiredAxis[t] > 0.0f) {
|
||||
rateDesiredAxis[t] = 0.0f;
|
||||
}
|
||||
}
|
||||
} else if (t == 0) { // roll
|
||||
if (attitudeState.Roll < -stabSettings.stabBank.RollMax) {
|
||||
// attitude exceeds roll max.
|
||||
// zero rate desired if also -ve
|
||||
if (rateDesiredAxis[t] < 0.0f) {
|
||||
rateDesiredAxis[t] = 0.0f;
|
||||
}
|
||||
} else if (attitudeState.Roll > stabSettings.stabBank.RollMax) {
|
||||
// attitude exceeds roll max
|
||||
// zero rate desired if also +ve
|
||||
if (rateDesiredAxis[t] > 0.0f) {
|
||||
rateDesiredAxis[t] = 0.0f;
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case STABILIZATIONSTATUS_OUTERLOOP_DIRECT:
|
||||
default:
|
||||
rateDesiredAxis[t] = stabilizationDesiredAxis[t];
|
||||
@ -264,7 +301,7 @@ static void stabilizationOuterloopTask()
|
||||
|
||||
RateDesiredSet(&rateDesired);
|
||||
{
|
||||
uint8_t armed;
|
||||
FlightStatusArmedOptions armed;
|
||||
FlightStatusArmedGet(&armed);
|
||||
float throttleDesired;
|
||||
ManualControlCommandThrottleGet(&throttleDesired);
|
||||
|
@ -137,6 +137,10 @@ static void StabilizationDesiredUpdatedCb(__attribute__((unused)) UAVObjEvent *e
|
||||
StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT;
|
||||
StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE;
|
||||
break;
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATETRAINER:
|
||||
StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECTWITHLIMITS;
|
||||
StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE;
|
||||
break;
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE:
|
||||
StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_ATTITUDE;
|
||||
StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE;
|
||||
|
@ -30,13 +30,17 @@
|
||||
*/
|
||||
|
||||
#include "inc/stateestimation.h"
|
||||
|
||||
// Fake pos rate in uS
|
||||
#define FILTERSTATIONARY_FAKEPOSRATE 100000
|
||||
// Private constants
|
||||
|
||||
#define STACK_REQUIRED 64
|
||||
#define STACK_REQUIRED 64
|
||||
|
||||
// Private types
|
||||
|
||||
// Private types
|
||||
struct data {
|
||||
uint32_t lastUpdate;
|
||||
};
|
||||
// Private variables
|
||||
|
||||
// Private functions
|
||||
@ -49,27 +53,34 @@ int32_t filterStationaryInitialize(stateFilter *handle)
|
||||
{
|
||||
handle->init = &init;
|
||||
handle->filter = &filter;
|
||||
handle->localdata = NULL;
|
||||
handle->localdata = pios_malloc(sizeof(struct data));
|
||||
return STACK_REQUIRED;
|
||||
}
|
||||
|
||||
static int32_t init(__attribute__((unused)) stateFilter *self)
|
||||
static int32_t init(stateFilter *self)
|
||||
{
|
||||
struct data *this = (struct data *)self->localdata;
|
||||
|
||||
this->lastUpdate = PIOS_DELAY_GetRaw();
|
||||
return 0;
|
||||
}
|
||||
|
||||
static filterResult filter(__attribute__((unused)) stateFilter *self, stateEstimation *state)
|
||||
static filterResult filter(stateFilter *self, stateEstimation *state)
|
||||
{
|
||||
state->pos[0] = 0.0f;
|
||||
state->pos[1] = 0.0f;
|
||||
state->pos[2] = 0.0f;
|
||||
state->updated |= SENSORUPDATES_pos;
|
||||
struct data *this = (struct data *)self->localdata;
|
||||
|
||||
state->vel[0] = 0.0f;
|
||||
state->vel[1] = 0.0f;
|
||||
state->vel[2] = 0.0f;
|
||||
state->updated |= SENSORUPDATES_vel;
|
||||
if (PIOS_DELAY_DiffuS(this->lastUpdate) > FILTERSTATIONARY_FAKEPOSRATE) {
|
||||
this->lastUpdate = PIOS_DELAY_GetRaw();
|
||||
state->pos[0] = 0.0f;
|
||||
state->pos[1] = 0.0f;
|
||||
state->pos[2] = 0.0f;
|
||||
state->updated |= SENSORUPDATES_pos;
|
||||
|
||||
state->vel[0] = 0.0f;
|
||||
state->vel[1] = 0.0f;
|
||||
state->vel[2] = 0.0f;
|
||||
state->updated |= SENSORUPDATES_vel;
|
||||
}
|
||||
return FILTERRESULT_OK;
|
||||
}
|
||||
|
||||
|
@ -101,7 +101,9 @@ static enum { STACKOVERFLOW_NONE = 0, STACKOVERFLOW_WARNING = 1, STACKOVERFLOW_C
|
||||
static bool mallocFailed;
|
||||
static HwSettingsData bootHwSettings;
|
||||
static FrameType_t bootFrameType;
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32)
|
||||
static struct PIOS_FLASHFS_Stats fsStats;
|
||||
#endif
|
||||
|
||||
// Private functions
|
||||
static void objectUpdatedCb(UAVObjEvent *ev);
|
||||
|
@ -888,7 +888,7 @@ static void updateSettings(channelContext *channel)
|
||||
|
||||
if (port) {
|
||||
// Retrieve settings
|
||||
uint8_t speed;
|
||||
HwSettingsTelemetrySpeedOptions speed;
|
||||
HwSettingsTelemetrySpeedGet(&speed);
|
||||
|
||||
// Set port speed
|
||||
|
@ -49,9 +49,8 @@ void handleMag()
|
||||
|
||||
if (PIOS_HMC5x83_ReadMag(onboard_mag, mag) == 0) {
|
||||
MagUbxPkt magPkt;
|
||||
// swap axis so that if side with connector is aligned to revo side with connectors, mags data are aligned
|
||||
magPkt.fragments.data.X = -mag[1];
|
||||
magPkt.fragments.data.Y = mag[0];
|
||||
magPkt.fragments.data.X = mag[0];
|
||||
magPkt.fragments.data.Y = mag[1];
|
||||
magPkt.fragments.data.Z = mag[2];
|
||||
magPkt.fragments.data.status = 1;
|
||||
ubx_buildPacket(&magPkt.packet, UBX_OP_CUST_CLASS, UBX_OP_MAG, sizeof(MagData));
|
||||
|
@ -224,7 +224,7 @@ int32_t PIOS_HMC5x83_ReadMag(pios_hmc5x83_dev_t handler, int16_t out[3])
|
||||
|
||||
dev->data_ready = false;
|
||||
uint8_t buffer[6];
|
||||
int32_t temp;
|
||||
int16_t temp[3];
|
||||
int32_t sensitivity;
|
||||
|
||||
if (dev->cfg->Driver->Read(handler, PIOS_HMC5x83_DATAOUT_XMSB_REG, buffer, 6) != 0) {
|
||||
@ -259,16 +259,54 @@ int32_t PIOS_HMC5x83_ReadMag(pios_hmc5x83_dev_t handler, int16_t out[3])
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
for (int i = 0; i < 3; i++) {
|
||||
temp = ((int16_t)((uint16_t)buffer[2 * i] << 8)
|
||||
+ buffer[2 * i + 1]) * 1000 / sensitivity;
|
||||
out[i] = temp;
|
||||
int16_t v = ((int16_t)((uint16_t)buffer[2 * i] << 8)
|
||||
+ buffer[2 * i + 1]) * 1000 / sensitivity;
|
||||
temp[i] = v;
|
||||
}
|
||||
|
||||
switch (dev->cfg->Orientation) {
|
||||
case PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP:
|
||||
out[0] = temp[2];
|
||||
out[1] = temp[0];
|
||||
out[2] = -temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_SOUTH_EAST_UP:
|
||||
out[0] = -temp[0];
|
||||
out[1] = temp[2];
|
||||
out[2] = -temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_WEST_SOUTH_UP:
|
||||
out[0] = -temp[2];
|
||||
out[1] = -temp[0];
|
||||
out[2] = -temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_NORTH_WEST_UP:
|
||||
out[0] = temp[0];
|
||||
out[1] = -temp[2];
|
||||
out[2] = -temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_EAST_SOUTH_DOWN:
|
||||
out[0] = temp[2];
|
||||
out[1] = -temp[0];
|
||||
out[2] = temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_SOUTH_WEST_DOWN:
|
||||
out[0] = -temp[0];
|
||||
out[1] = -temp[2];
|
||||
out[2] = temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_WEST_NORTH_DOWN:
|
||||
out[0] = -temp[2];
|
||||
out[1] = temp[0];
|
||||
out[2] = temp[1];
|
||||
break;
|
||||
case PIOS_HMC5X83_ORIENTATION_NORTH_EAST_DOWN:
|
||||
out[0] = temp[0];
|
||||
out[1] = temp[2];
|
||||
out[2] = temp[1];
|
||||
break;
|
||||
}
|
||||
// Data reads out as X,Z,Y
|
||||
temp = out[2];
|
||||
out[2] = out[1];
|
||||
out[1] = temp;
|
||||
|
||||
// This should not be necessary but for some reason it is coming out of continuous conversion mode
|
||||
dev->cfg->Driver->Write(handler, PIOS_HMC5x83_MODE_REG, PIOS_HMC5x83_MODE_CONTINUOUS);
|
||||
|
365
flight/pios/common/pios_srxl.c
Normal file
365
flight/pios/common/pios_srxl.c
Normal file
@ -0,0 +1,365 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SRXL Multiplex SRXL receiver functions
|
||||
* @brief Code to read Multiplex SRXL receiver serial stream
|
||||
* @{
|
||||
*
|
||||
* @file pios_srxl.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015.
|
||||
* @brief Code to read Multiplex SRXL receiver serial stream
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "pios.h"
|
||||
|
||||
#ifdef PIOS_INCLUDE_SRXL
|
||||
|
||||
#include "pios_srxl_priv.h"
|
||||
|
||||
// #define PIOS_INSTRUMENT_MODULE
|
||||
#include <pios_instrumentation_helper.h>
|
||||
|
||||
PERF_DEFINE_COUNTER(crcFailureCount);
|
||||
PERF_DEFINE_COUNTER(failsafeCount);
|
||||
PERF_DEFINE_COUNTER(successfulCount);
|
||||
PERF_DEFINE_COUNTER(messageUnrollTimer);
|
||||
PERF_DEFINE_COUNTER(messageReceiveRate);
|
||||
PERF_DEFINE_COUNTER(receivedBytesCount);
|
||||
PERF_DEFINE_COUNTER(frameStartCount);
|
||||
PERF_DEFINE_COUNTER(frameAbortCount);
|
||||
PERF_DEFINE_COUNTER(completeMessageCount);
|
||||
|
||||
/* Forward Declarations */
|
||||
static int32_t PIOS_SRXL_Get(uint32_t rcvr_id, uint8_t channel);
|
||||
static uint16_t PIOS_SRXL_RxInCallback(uint32_t context,
|
||||
uint8_t *buf,
|
||||
uint16_t buf_len,
|
||||
uint16_t *headroom,
|
||||
bool *need_yield);
|
||||
static void PIOS_SRXL_Supervisor(uint32_t srxl_id);
|
||||
|
||||
|
||||
/* Local Variables */
|
||||
const struct pios_rcvr_driver pios_srxl_rcvr_driver = {
|
||||
.read = PIOS_SRXL_Get,
|
||||
};
|
||||
|
||||
enum pios_srxl_dev_magic {
|
||||
PIOS_SRXL_DEV_MAGIC = 0x55545970,
|
||||
};
|
||||
|
||||
struct pios_srxl_state {
|
||||
uint16_t channel_data[PIOS_SRXL_NUM_INPUTS];
|
||||
uint8_t received_data[SRXL_FRAME_LENGTH];
|
||||
uint8_t receive_timer;
|
||||
uint8_t failsafe_timer;
|
||||
uint8_t frame_found;
|
||||
uint8_t byte_count;
|
||||
uint8_t data_bytes;
|
||||
};
|
||||
|
||||
struct pios_srxl_dev {
|
||||
enum pios_srxl_dev_magic magic;
|
||||
struct pios_srxl_state state;
|
||||
};
|
||||
|
||||
/* Allocate S.Bus device descriptor */
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static struct pios_srxl_dev *PIOS_SRXL_Alloc(void)
|
||||
{
|
||||
struct pios_srxl_dev *srxl_dev;
|
||||
|
||||
srxl_dev = (struct pios_srxl_dev *)pios_malloc(sizeof(*srxl_dev));
|
||||
if (!srxl_dev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
srxl_dev->magic = PIOS_SRXL_DEV_MAGIC;
|
||||
return srxl_dev;
|
||||
}
|
||||
#else
|
||||
static struct pios_srxl_dev pios_srxl_devs[PIOS_SRXL_MAX_DEVS];
|
||||
static uint8_t pios_srxl_num_devs;
|
||||
static struct pios_srxl_dev *PIOS_SRXL_Alloc(void)
|
||||
{
|
||||
struct pios_srxl_dev *srxl_dev;
|
||||
|
||||
if (pios_srxl_num_devs >= PIOS_SRXL_MAX_DEVS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
srxl_dev = &pios_srxl_devs[pios_srxl_num_devs++];
|
||||
srxl_dev->magic = PIOS_SRXL_DEV_MAGIC;
|
||||
|
||||
return srxl_dev;
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_FREERTOS) */
|
||||
|
||||
/* Validate SRXL device descriptor */
|
||||
static bool PIOS_SRXL_Validate(struct pios_srxl_dev *srxl_dev)
|
||||
{
|
||||
return srxl_dev->magic == PIOS_SRXL_DEV_MAGIC;
|
||||
}
|
||||
|
||||
/* Reset channels in case of lost signal or explicit failsafe receiver flag */
|
||||
static void PIOS_SRXL_ResetChannels(struct pios_srxl_state *state)
|
||||
{
|
||||
for (int i = 0; i < PIOS_SRXL_NUM_INPUTS; i++) {
|
||||
state->channel_data[i] = PIOS_RCVR_TIMEOUT;
|
||||
}
|
||||
}
|
||||
|
||||
/* Reset SRXL receiver state */
|
||||
static void PIOS_SRXL_ResetState(struct pios_srxl_state *state)
|
||||
{
|
||||
state->receive_timer = 0;
|
||||
state->failsafe_timer = 0;
|
||||
state->frame_found = 0;
|
||||
state->data_bytes = 0;
|
||||
PIOS_SRXL_ResetChannels(state);
|
||||
}
|
||||
|
||||
/* Initialize SRXL receiver interface */
|
||||
int32_t PIOS_SRXL_Init(uint32_t *srxl_id,
|
||||
const struct pios_com_driver *driver,
|
||||
uint32_t lower_id)
|
||||
{
|
||||
PIOS_DEBUG_Assert(srxl_id);
|
||||
PIOS_DEBUG_Assert(driver);
|
||||
|
||||
struct pios_srxl_dev *srxl_dev;
|
||||
|
||||
srxl_dev = (struct pios_srxl_dev *)PIOS_SRXL_Alloc();
|
||||
if (!srxl_dev) {
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
PIOS_SRXL_ResetState(&(srxl_dev->state));
|
||||
|
||||
*srxl_id = (uint32_t)srxl_dev;
|
||||
|
||||
/* Set comm driver callback */
|
||||
(driver->bind_rx_cb)(lower_id, PIOS_SRXL_RxInCallback, *srxl_id);
|
||||
|
||||
if (!PIOS_RTC_RegisterTickCallback(PIOS_SRXL_Supervisor, *srxl_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
PERF_INIT_COUNTER(crcFailureCount, 0x5551);
|
||||
PERF_INIT_COUNTER(failsafeCount, 0x5552);
|
||||
PERF_INIT_COUNTER(successfulCount, 0x5553);
|
||||
PERF_INIT_COUNTER(messageUnrollTimer, 0x5554);
|
||||
PERF_INIT_COUNTER(messageReceiveRate, 0x5555);
|
||||
PERF_INIT_COUNTER(receivedBytesCount, 0x5556);
|
||||
PERF_INIT_COUNTER(frameStartCount, 0x5557);
|
||||
PERF_INIT_COUNTER(frameAbortCount, 0x5558);
|
||||
PERF_INIT_COUNTER(completeMessageCount, 0x5559);
|
||||
|
||||
return 0;
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the value of an input channel
|
||||
* \param[in] channel Number of the channel desired (zero based)
|
||||
* \output PIOS_RCVR_INVALID channel not available
|
||||
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||
* \output >=0 channel value
|
||||
*/
|
||||
static int32_t PIOS_SRXL_Get(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
struct pios_srxl_dev *srxl_dev = (struct pios_srxl_dev *)rcvr_id;
|
||||
|
||||
if (!PIOS_SRXL_Validate(srxl_dev)) {
|
||||
return PIOS_RCVR_INVALID;
|
||||
}
|
||||
|
||||
/* return error if channel is not available */
|
||||
if (channel >= PIOS_SRXL_NUM_INPUTS) {
|
||||
return PIOS_RCVR_INVALID;
|
||||
}
|
||||
|
||||
return srxl_dev->state.channel_data[channel];
|
||||
}
|
||||
|
||||
static void PIOS_SRXL_UnrollChannels(struct pios_srxl_state *state)
|
||||
{
|
||||
PERF_TIMED_SECTION_START(messageUnrollTimer);
|
||||
uint8_t *received_data = state->received_data;
|
||||
uint8_t channel;
|
||||
uint16_t channel_value;
|
||||
for (channel = 0; channel < (state->data_bytes / 2); channel++) {
|
||||
channel_value = ((uint16_t)received_data[SRXL_HEADER_LENGTH + (channel * 2)]) << 8;
|
||||
channel_value = channel_value + ((uint16_t)received_data[SRXL_HEADER_LENGTH + (channel * 2) + 1]);
|
||||
state->channel_data[channel] = (800 + ((channel_value * 1400) >> 12));
|
||||
}
|
||||
PERF_TIMED_SECTION_END(messageUnrollTimer);
|
||||
}
|
||||
|
||||
static bool PIOS_SRXL_Validate_Checksum(struct pios_srxl_state *state)
|
||||
{
|
||||
// Check the CRC16 checksum. The provided checksum is immediately after the channel data.
|
||||
// All data including start byte and version byte is included in crc calculation.
|
||||
uint8_t i = 0;
|
||||
uint16_t crc = 0;
|
||||
|
||||
for (i = 0; i < SRXL_HEADER_LENGTH + state->data_bytes; i++) {
|
||||
crc = crc ^ (int16_t)state->received_data[i] << 8;
|
||||
uint8_t j = 0;
|
||||
for (j = 0; j < 8; j++) {
|
||||
if (crc & 0x8000) {
|
||||
crc = crc << 1 ^ 0x1021;
|
||||
} else {
|
||||
crc = crc << 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
uint16_t checksum = (((uint16_t)(state->received_data[i] << 8) |
|
||||
(uint16_t)state->received_data[i + 1]));
|
||||
return crc == checksum;
|
||||
}
|
||||
|
||||
/* Update decoder state processing input byte from the SRXL stream */
|
||||
static void PIOS_SRXL_UpdateState(struct pios_srxl_state *state, uint8_t b)
|
||||
{
|
||||
/* should not process any data until new frame is found */
|
||||
if (!state->frame_found) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (state->byte_count < (SRXL_HEADER_LENGTH + state->data_bytes + SRXL_CHECKSUM_LENGTH)) {
|
||||
if (state->byte_count == 0) {
|
||||
// Set up the length of the channel data according to version received
|
||||
PERF_INCREMENT_VALUE(frameStartCount);
|
||||
if (b == SRXL_V1_HEADER) {
|
||||
state->data_bytes = SRXL_V1_CHANNEL_DATA_BYTES;
|
||||
} else if (b == SRXL_V2_HEADER) {
|
||||
state->data_bytes = SRXL_V2_CHANNEL_DATA_BYTES;
|
||||
} else {
|
||||
/* discard the whole frame if the 1st byte is not correct */
|
||||
state->frame_found = 0;
|
||||
PERF_INCREMENT_VALUE(frameAbortCount);
|
||||
return;
|
||||
}
|
||||
}
|
||||
/* store next byte */
|
||||
state->received_data[state->byte_count] = b;
|
||||
state->byte_count++;
|
||||
if (state->byte_count == (SRXL_HEADER_LENGTH + state->data_bytes + SRXL_CHECKSUM_LENGTH)) {
|
||||
PERF_INCREMENT_VALUE(completeMessageCount);
|
||||
// We have a complete message, lets decode it
|
||||
if (PIOS_SRXL_Validate_Checksum(state)) {
|
||||
/* data looking good */
|
||||
PIOS_SRXL_UnrollChannels(state);
|
||||
state->failsafe_timer = 0;
|
||||
PERF_INCREMENT_VALUE(successfulCount);
|
||||
} else {
|
||||
/* discard whole frame */
|
||||
PERF_INCREMENT_VALUE(crcFailureCount);
|
||||
}
|
||||
/* prepare for the next frame */
|
||||
state->frame_found = 0;
|
||||
PERF_MEASURE_PERIOD(messageReceiveRate);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Comm byte received callback */
|
||||
static uint16_t PIOS_SRXL_RxInCallback(uint32_t context,
|
||||
uint8_t *buf,
|
||||
uint16_t buf_len,
|
||||
uint16_t *headroom,
|
||||
bool *need_yield)
|
||||
{
|
||||
struct pios_srxl_dev *srxl_dev = (struct pios_srxl_dev *)context;
|
||||
|
||||
bool valid = PIOS_SRXL_Validate(srxl_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
struct pios_srxl_state *state = &(srxl_dev->state);
|
||||
|
||||
/* process byte(s) and clear receive timer */
|
||||
for (uint8_t i = 0; i < buf_len; i++) {
|
||||
PIOS_SRXL_UpdateState(state, buf[i]);
|
||||
state->receive_timer = 0;
|
||||
PERF_INCREMENT_VALUE(receivedBytesCount);
|
||||
}
|
||||
|
||||
/* Always signal that we can accept another byte */
|
||||
if (headroom) {
|
||||
*headroom = SRXL_FRAME_LENGTH;
|
||||
}
|
||||
|
||||
/* We never need a yield */
|
||||
*need_yield = false;
|
||||
|
||||
/* Always indicate that all bytes were consumed */
|
||||
return buf_len;
|
||||
}
|
||||
|
||||
/**
|
||||
* Input data supervisor is called periodically and provides
|
||||
* two functions: frame syncing and failsafe triggering.
|
||||
*
|
||||
* Multiplex SRXL frames come at 14ms (FastResponse ON) or 21ms (FastResponse OFF)
|
||||
* rate at 115200bps.
|
||||
* RTC timer is running at 625Hz (1.6ms). So with divider 2 it gives
|
||||
* 3.2ms pause between frames which is good for both SRXL frame rates.
|
||||
*
|
||||
* Data receive function must clear the receive_timer to confirm new
|
||||
* data reception. If no new data received in 100ms, we must call the
|
||||
* failsafe function which clears all channels.
|
||||
*/
|
||||
static void PIOS_SRXL_Supervisor(uint32_t srxl_id)
|
||||
{
|
||||
struct pios_srxl_dev *srxl_dev = (struct pios_srxl_dev *)srxl_id;
|
||||
|
||||
bool valid = PIOS_SRXL_Validate(srxl_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
struct pios_srxl_state *state = &(srxl_dev->state);
|
||||
|
||||
/* waiting for new frame if no bytes were received in 6.4ms */
|
||||
|
||||
if (++state->receive_timer > 4) {
|
||||
state->frame_found = 1;
|
||||
state->byte_count = 0;
|
||||
state->receive_timer = 0;
|
||||
}
|
||||
|
||||
/* activate failsafe if no frames have arrived in 102.4ms */
|
||||
if (++state->failsafe_timer > 64) {
|
||||
PIOS_SRXL_ResetChannels(state);
|
||||
state->failsafe_timer = 0;
|
||||
PERF_INCREMENT_VALUE(failsafeCount);
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SRXL */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -38,6 +38,7 @@ typedef void (*ADCCallback)(float *data);
|
||||
|
||||
/* Public Functions */
|
||||
void PIOS_ADC_Config(uint32_t oversampling);
|
||||
void PIOS_ADC_PinSetup(uint32_t pin);
|
||||
int32_t PIOS_ADC_PinGet(uint32_t pin);
|
||||
float PIOS_ADC_PinGetVolt(uint32_t pin);
|
||||
int16_t *PIOS_ADC_GetRawBuffer(void);
|
||||
|
@ -109,6 +109,18 @@ extern const struct pios_hmc5x83_io_driver PIOS_HMC5x83_SPI_DRIVER;
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
extern const struct pios_hmc5x83_io_driver PIOS_HMC5x83_I2C_DRIVER;
|
||||
#endif
|
||||
// xyz axis orientation
|
||||
enum PIOS_HMC5X83_ORIENTATION {
|
||||
PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
PIOS_HMC5X83_ORIENTATION_SOUTH_EAST_UP,
|
||||
PIOS_HMC5X83_ORIENTATION_WEST_SOUTH_UP,
|
||||
PIOS_HMC5X83_ORIENTATION_NORTH_WEST_UP,
|
||||
PIOS_HMC5X83_ORIENTATION_EAST_SOUTH_DOWN,
|
||||
PIOS_HMC5X83_ORIENTATION_SOUTH_WEST_DOWN,
|
||||
PIOS_HMC5X83_ORIENTATION_WEST_NORTH_DOWN,
|
||||
PIOS_HMC5X83_ORIENTATION_NORTH_EAST_DOWN,
|
||||
};
|
||||
|
||||
|
||||
struct pios_hmc5x83_cfg {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
@ -119,6 +131,7 @@ struct pios_hmc5x83_cfg {
|
||||
uint8_t Gain; // Gain Configuration, select the full scale --> here below the relative define (See datasheet page 11 for more details) */
|
||||
uint8_t Mode;
|
||||
bool TempCompensation; // enable temperature sensor on HMC5983 for temperature gain compensation
|
||||
enum PIOS_HMC5X83_ORIENTATION Orientation;
|
||||
const struct pios_hmc5x83_io_driver *Driver;
|
||||
};
|
||||
|
||||
|
@ -47,7 +47,7 @@ extern int8_t pios_instrumentation_last_used_counter;
|
||||
* @param counter_handle handle of the counter to update @see PIOS_Instrumentation_SearchCounter @see PIOS_Instrumentation_CreateCounter
|
||||
* @param newValue the updated value.
|
||||
*/
|
||||
inline void PIOS_Instrumentation_updateCounter(pios_counter_t counter_handle, int32_t newValue)
|
||||
static inline void PIOS_Instrumentation_updateCounter(pios_counter_t counter_handle, int32_t newValue)
|
||||
{
|
||||
PIOS_Assert(pios_instrumentation_perf_counters && counter_handle);
|
||||
vPortEnterCritical();
|
||||
@ -69,7 +69,7 @@ inline void PIOS_Instrumentation_updateCounter(pios_counter_t counter_handle, in
|
||||
* Used to determine the time duration of a code block, mark the begin of the block. @see PIOS_Instrumentation_TimeEnd
|
||||
* @param counter_handle handle of the counter @see PIOS_Instrumentation_SearchCounter @see PIOS_Instrumentation_CreateCounter
|
||||
*/
|
||||
inline void PIOS_Instrumentation_TimeStart(pios_counter_t counter_handle)
|
||||
static inline void PIOS_Instrumentation_TimeStart(pios_counter_t counter_handle)
|
||||
{
|
||||
PIOS_Assert(pios_instrumentation_perf_counters && counter_handle);
|
||||
vPortEnterCritical();
|
||||
@ -83,7 +83,7 @@ inline void PIOS_Instrumentation_TimeStart(pios_counter_t counter_handle)
|
||||
* Used to determine the time duration of a code block, mark the end of the block. @see PIOS_Instrumentation_TimeStart
|
||||
* @param counter_handle handle of the counter @see PIOS_Instrumentation_SearchCounter @see PIOS_Instrumentation_CreateCounter
|
||||
*/
|
||||
inline void PIOS_Instrumentation_TimeEnd(pios_counter_t counter_handle)
|
||||
static inline void PIOS_Instrumentation_TimeEnd(pios_counter_t counter_handle)
|
||||
{
|
||||
PIOS_Assert(pios_instrumentation_perf_counters && counter_handle);
|
||||
vPortEnterCritical();
|
||||
@ -106,7 +106,7 @@ inline void PIOS_Instrumentation_TimeEnd(pios_counter_t counter_handle)
|
||||
* Used to determine the mean period between each call to the function
|
||||
* @param counter_handle handle of the counter @see PIOS_Instrumentation_SearchCounter @see PIOS_Instrumentation_CreateCounter
|
||||
*/
|
||||
inline void PIOS_Instrumentation_TrackPeriod(pios_counter_t counter_handle)
|
||||
static inline void PIOS_Instrumentation_TrackPeriod(pios_counter_t counter_handle)
|
||||
{
|
||||
PIOS_Assert(pios_instrumentation_perf_counters && counter_handle);
|
||||
pios_perf_counter_t *counter = (pios_perf_counter_t *)counter_handle;
|
||||
@ -127,6 +127,29 @@ inline void PIOS_Instrumentation_TrackPeriod(pios_counter_t counter_handle)
|
||||
counter->lastUpdateTS = PIOS_DELAY_GetRaw();
|
||||
}
|
||||
|
||||
/**
|
||||
* Increment a counter with a value
|
||||
* @param counter_handle handle of the counter to update @see PIOS_Instrumentation_SearchCounter @see PIOS_Instrumentation_CreateCounter
|
||||
* @param increment the value to increment counter with.
|
||||
*/
|
||||
static inline void PIOS_Instrumentation_incrementCounter(pios_counter_t counter_handle, int32_t increment)
|
||||
{
|
||||
PIOS_Assert(pios_instrumentation_perf_counters && counter_handle);
|
||||
vPortEnterCritical();
|
||||
pios_perf_counter_t *counter = (pios_perf_counter_t *)counter_handle;
|
||||
counter->value += increment;
|
||||
counter->max--;
|
||||
if (counter->value > counter->max) {
|
||||
counter->max = counter->value;
|
||||
}
|
||||
counter->min++;
|
||||
if (counter->value < counter->min) {
|
||||
counter->min = counter->value;
|
||||
}
|
||||
counter->lastUpdateTS = PIOS_DELAY_GetRaw();
|
||||
vPortExitCritical();
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize the Instrumentation infrastructure
|
||||
* @param maxCounters maximum number of allowed counters
|
||||
|
@ -98,6 +98,8 @@
|
||||
#define PERF_TIMED_SECTION_END(x) PIOS_Instrumentation_TimeEnd(x)
|
||||
#define PERF_MEASURE_PERIOD(x) PIOS_Instrumentation_TrackPeriod(x)
|
||||
#define PERF_TRACK_VALUE(x, y) PIOS_Instrumentation_updateCounter(x, y)
|
||||
#define PERF_INCREMENT_VALUE(x) PIOS_Instrumentation_incrementCounter(x, 1)
|
||||
#define PERF_DECREMENT_VALUE(x) PIOS_Instrumentation_incrementCounter(x, -1)
|
||||
|
||||
#else
|
||||
|
||||
@ -107,5 +109,7 @@
|
||||
#define PERF_TIMED_SECTION_END(x)
|
||||
#define PERF_MEASURE_PERIOD(x)
|
||||
#define PERF_TRACK_VALUE(x, y)
|
||||
#define PERF_INCREMENT_VALUE(x)
|
||||
#define PERF_DECREMENT_VALUE(x)
|
||||
#endif /* PIOS_INCLUDE_INSTRUMENTATION */
|
||||
#endif /* PIOS_INSTRUMENTATION_HELPER_H */
|
||||
|
43
flight/pios/inc/pios_srxl.h
Normal file
43
flight/pios/inc/pios_srxl.h
Normal file
@ -0,0 +1,43 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SRXL Multiplex SRXL receiver functions
|
||||
* @brief Code to read Multiplex SRXL receiver serial stream
|
||||
* @{
|
||||
*
|
||||
* @file pios_srxl.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015.
|
||||
* @brief Code to read Multiplex SRXL receiver serial stream
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_SRXL_H
|
||||
#define PIOS_SRXL_H
|
||||
|
||||
/* Global Types */
|
||||
|
||||
/* Public Functions */
|
||||
|
||||
#endif /* PIOS_SRXL_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
95
flight/pios/inc/pios_srxl_priv.h
Normal file
95
flight/pios/inc/pios_srxl_priv.h
Normal file
@ -0,0 +1,95 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SRXL Multiplex SRXL receiver functions
|
||||
* @brief Code to read Multiplex SRXL receiver serial stream
|
||||
* @{
|
||||
*
|
||||
* @file pios_srxl_priv.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015.
|
||||
* @brief Code to read Multiplex SRXL receiver serial stream
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_SRXL_PRIV_H
|
||||
#define PIOS_SRXL_PRIV_H
|
||||
|
||||
#include <pios.h>
|
||||
#include <pios_stm32.h>
|
||||
#include <pios_usart_priv.h>
|
||||
|
||||
/*
|
||||
* Multiplex SRXL serial port settings:
|
||||
* 115200bps inverted serial stream, 8 bits, no parity, 1 stop bits
|
||||
* frame period is 14ms (FastResponse ON) or 21ms (FastResponse OFF)
|
||||
*
|
||||
* Frame structure:
|
||||
* 1 byte - start and version
|
||||
* 0xa1 (v1 12-channels)
|
||||
* 0xa2 (v2 16-channels)
|
||||
* 24/32 bytes - channel data (4 + 12 bit/channel, 12/16 channels, MSB first)
|
||||
* 16 bits per channel. 4 first reserved/not used. 12 bits channel data in
|
||||
* 4095 steps, 0x000(800µs) - 0x800(1500µs) - 0xfff(2200µs)
|
||||
* 2 bytes checksum (calculated over all bytes including start and version)
|
||||
*
|
||||
* Checksum calculation:
|
||||
* u16 CRC16(u16 crc, u8 value) {
|
||||
* u8 i;
|
||||
* crc = crc ^ (s16)value << 8;
|
||||
* for(i = 0; i < 8; i++) {
|
||||
* if(crc & 0x8000) {
|
||||
* crc = crc << 1 ^ 0x1021;
|
||||
* } else {
|
||||
* crc = crc << 1;
|
||||
* }
|
||||
* }
|
||||
* return crc;
|
||||
* }
|
||||
*/
|
||||
|
||||
#define SRXL_V1_HEADER 0xa1
|
||||
#define SRXL_V2_HEADER 0xa2
|
||||
|
||||
#define SRXL_HEADER_LENGTH 1
|
||||
#define SRXL_CHECKSUM_LENGTH 2
|
||||
#define SRXL_V1_CHANNEL_DATA_BYTES (12 * 2)
|
||||
#define SRXL_V2_CHANNEL_DATA_BYTES (16 * 2)
|
||||
#define SRXL_FRAME_LENGTH (SRXL_HEADER_LENGTH + SRXL_V2_CHANNEL_DATA_BYTES + SRXL_CHECKSUM_LENGTH)
|
||||
|
||||
/*
|
||||
* Multiplex SRXL protocol provides 16 proportional channels.
|
||||
* Do not change unless driver code is updated accordingly.
|
||||
*/
|
||||
#if (PIOS_SRXL_NUM_INPUTS != 16)
|
||||
#error "Multiplex SRXL protocol provides 16 proportional channels."
|
||||
#endif
|
||||
|
||||
extern const struct pios_rcvr_driver pios_srxl_rcvr_driver;
|
||||
|
||||
extern int32_t PIOS_SRXL_Init(uint32_t *srxl_id,
|
||||
const struct pios_com_driver *driver,
|
||||
uint32_t lower_id);
|
||||
|
||||
#endif /* PIOS_SRXL_PRIV_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -228,6 +228,10 @@ extern "C" {
|
||||
#include <pios_sbus.h>
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_SRXL
|
||||
#include <pios_srxl.h>
|
||||
#endif
|
||||
|
||||
/* PIOS abstract receiver interface */
|
||||
#ifdef PIOS_INCLUDE_RCVR
|
||||
#include <pios_rcvr.h>
|
||||
|
@ -209,9 +209,7 @@ static void PIOS_PWM_tim_overflow_cb(__attribute__((unused)) uint32_t tim_id, ui
|
||||
/* Channel out of range */
|
||||
return;
|
||||
}
|
||||
if (!pwm_dev->CaptureState[channel]) {
|
||||
return;
|
||||
}
|
||||
|
||||
pwm_dev->us_since_update[channel] += count;
|
||||
if (pwm_dev->us_since_update[channel] >= PWM_SUPERVISOR_TIMEOUT) {
|
||||
pwm_dev->CaptureState[channel] = 0;
|
||||
|
@ -99,10 +99,11 @@ static void init_dma(void);
|
||||
static void init_adc(void);
|
||||
#endif
|
||||
|
||||
struct dma_config {
|
||||
struct pios_adc_pin_config {
|
||||
GPIO_TypeDef *port;
|
||||
uint32_t pin;
|
||||
uint32_t channel;
|
||||
bool initialize;
|
||||
};
|
||||
|
||||
struct adc_accumulator {
|
||||
@ -111,7 +112,7 @@ struct adc_accumulator {
|
||||
};
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
static const struct dma_config config[] = PIOS_DMA_PIN_CONFIG;
|
||||
static const struct pios_adc_pin_config config[] = PIOS_DMA_PIN_CONFIG;
|
||||
#define PIOS_ADC_NUM_PINS (sizeof(config) / sizeof(config[0]))
|
||||
|
||||
static struct adc_accumulator accumulator[PIOS_ADC_NUM_PINS];
|
||||
@ -123,18 +124,11 @@ static uint16_t adc_raw_buffer[2][PIOS_ADC_MAX_SAMPLES][PIOS_ADC_NUM_PINS];
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
static void init_pins(void)
|
||||
{
|
||||
/* Setup analog pins */
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN;
|
||||
for (uint32_t i = 0; i < PIOS_ADC_NUM_PINS; ++i) {
|
||||
if (config[i].port == NULL) {
|
||||
if (!config[i].initialize) {
|
||||
continue;
|
||||
}
|
||||
GPIO_InitStructure.GPIO_Pin = config[i].pin;
|
||||
GPIO_Init(config[i].port, &GPIO_InitStructure);
|
||||
PIOS_ADC_PinSetup(i);
|
||||
}
|
||||
}
|
||||
|
||||
@ -454,6 +448,19 @@ void PIOS_ADC_DMA_Handler(void)
|
||||
#endif
|
||||
}
|
||||
|
||||
void PIOS_ADC_PinSetup(uint32_t pin)
|
||||
{
|
||||
if (config[pin].port != NULL && pin < PIOS_ADC_NUM_PINS) {
|
||||
/* Setup analog pin */
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN;
|
||||
GPIO_InitStructure.GPIO_Pin = config[pin].pin;
|
||||
GPIO_Init(config[pin].port, &GPIO_InitStructure);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_ADC */
|
||||
|
||||
/**
|
||||
|
@ -20,6 +20,7 @@
|
||||
# (all architectures)
|
||||
UAVOBJSRCFILENAMES =
|
||||
UAVOBJSRCFILENAMES += statusvtolland
|
||||
UAVOBJSRCFILENAMES += statusvtolautotakeoff
|
||||
UAVOBJSRCFILENAMES += vtolselftuningstats
|
||||
UAVOBJSRCFILENAMES += accelgyrosettings
|
||||
UAVOBJSRCFILENAMES += accessorydesired
|
||||
|
@ -124,12 +124,13 @@ static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
};
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
@ -908,6 +909,17 @@ void PIOS_Board_Init(void)
|
||||
#include <pios_ws2811.h>
|
||||
PIOS_WS2811_Init(&pios_ws2811_cfg, &pios_ws2811_pin_cfg);
|
||||
#endif // PIOS_INCLUDE_WS2811
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
{
|
||||
uint8_t adc_config[HWSETTINGS_ADCROUTING_NUMELEM];
|
||||
HwSettingsADCRoutingArrayGet(adc_config);
|
||||
for (uint32_t i = 0; i < HWSETTINGS_ADCROUTING_NUMELEM; i++) {
|
||||
if (adc_config[i] != HWSETTINGS_ADCROUTING_DISABLED) {
|
||||
PIOS_ADC_PinSetup(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // PIOS_INCLUDE_ADC
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -264,10 +264,10 @@ extern uint32_t pios_packet_handler;
|
||||
// -------------------------
|
||||
#define PIOS_DMA_PIN_CONFIG \
|
||||
{ \
|
||||
{ GPIOC, GPIO_Pin_1, ADC_Channel_11 }, \
|
||||
{ GPIOC, GPIO_Pin_2, ADC_Channel_12 }, \
|
||||
{ NULL, 0, ADC_Channel_Vrefint }, /* Voltage reference */ \
|
||||
{ NULL, 0, ADC_Channel_TempSensor }, /* Temperature sensor */ \
|
||||
{ GPIOC, GPIO_Pin_1, ADC_Channel_11, false }, \
|
||||
{ GPIOC, GPIO_Pin_2, ADC_Channel_12, false }, \
|
||||
{ NULL, 0, ADC_Channel_Vrefint, false }, /* Voltage reference */ \
|
||||
{ NULL, 0, ADC_Channel_TempSensor, false }, /* Temperature sensor */ \
|
||||
}
|
||||
|
||||
/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */
|
||||
|
@ -246,14 +246,15 @@ static const struct pios_exti_cfg pios_exti_mag_cfg __exti_config = {
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_mag_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = &pios_exti_mag_cfg,
|
||||
.exti_cfg = &pios_exti_mag_cfg,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_30,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_30,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_3,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_SPI_DRIVER,
|
||||
.Driver = &PIOS_HMC5x83_SPI_DRIVER,
|
||||
.TempCompensation = true,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_WEST_NORTH_DOWN,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5883 */
|
||||
|
||||
|
@ -449,6 +449,17 @@ void PIOS_Board_Init(void)
|
||||
// PIOS_TIM_InitClock(&pios_tim4_cfg);
|
||||
PIOS_Video_Init(&pios_video_cfg);
|
||||
#endif
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
{
|
||||
uint8_t adc_config[HWSETTINGS_ADCROUTING_NUMELEM];
|
||||
HwSettingsADCRoutingArrayGet(adc_config);
|
||||
for (uint32_t i = 0; i < HWSETTINGS_ADCROUTING_NUMELEM; i++) {
|
||||
if (adc_config[i] != HWSETTINGS_ADCROUTING_DISABLED) {
|
||||
PIOS_ADC_PinSetup(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // PIOS_INCLUDE_ADC
|
||||
}
|
||||
|
||||
uint16_t supv_timer = 0;
|
||||
|
@ -208,13 +208,13 @@ extern uint32_t pios_com_telem_usb_id;
|
||||
|
||||
#define PIOS_DMA_PIN_CONFIG \
|
||||
{ \
|
||||
{ GPIOC, GPIO_Pin_0, ADC_Channel_10 }, \
|
||||
{ GPIOC, GPIO_Pin_1, ADC_Channel_11 }, \
|
||||
{ GPIOC, GPIO_Pin_2, ADC_Channel_12 }, \
|
||||
{ NULL, 0, ADC_Channel_TempSensor }, /* Temperature sensor */ \
|
||||
{ GPIOC, GPIO_Pin_3, ADC_Channel_13 }, \
|
||||
{ GPIOA, GPIO_Pin_7, ADC_Channel_7 }, \
|
||||
{ NULL, 0, ADC_Channel_Vrefint } /* Voltage reference */ \
|
||||
{ GPIOC, GPIO_Pin_0, ADC_Channel_10, true }, \
|
||||
{ GPIOC, GPIO_Pin_1, ADC_Channel_11, true }, \
|
||||
{ GPIOC, GPIO_Pin_2, ADC_Channel_12, true }, \
|
||||
{ NULL, 0, ADC_Channel_TempSensor, true }, /* Temperature sensor */ \
|
||||
{ GPIOC, GPIO_Pin_3, ADC_Channel_13, true }, \
|
||||
{ GPIOA, GPIO_Pin_7, ADC_Channel_7, true }, \
|
||||
{ NULL, 0, ADC_Channel_Vrefint, true } /* Voltage reference */ \
|
||||
}
|
||||
|
||||
/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */
|
||||
|
@ -899,7 +899,6 @@ static const struct pios_sbus_cfg pios_sbus_cfg = {
|
||||
.gpio_clk_periph = RCC_AHB1Periph_GPIOC,
|
||||
};
|
||||
|
||||
|
||||
#ifdef PIOS_INCLUDE_COM_FLEXI
|
||||
/*
|
||||
* FLEXI PORT
|
||||
@ -1007,6 +1006,54 @@ static const struct pios_dsm_cfg pios_dsm_flexi_cfg = {
|
||||
|
||||
#endif /* PIOS_INCLUDE_DSM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SRXL)
|
||||
/*
|
||||
* SRXL USART
|
||||
*/
|
||||
#include <pios_srxl_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_srxl_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_AF_USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_SRXL */
|
||||
/*
|
||||
* HK OSD
|
||||
*/
|
||||
|
@ -20,6 +20,7 @@
|
||||
# (all architectures)
|
||||
UAVOBJSRCFILENAMES =
|
||||
UAVOBJSRCFILENAMES += statusgrounddrive
|
||||
UAVOBJSRCFILENAMES += statusvtolautotakeoff
|
||||
UAVOBJSRCFILENAMES += pidstatus
|
||||
UAVOBJSRCFILENAMES += statusvtolland
|
||||
UAVOBJSRCFILENAMES += vtolselftuningstats
|
||||
|
@ -103,6 +103,7 @@
|
||||
/* #define PIOS_INCLUDE_PPM_FLEXI */
|
||||
#define PIOS_INCLUDE_DSM
|
||||
#define PIOS_INCLUDE_SBUS
|
||||
#define PIOS_INCLUDE_SRXL
|
||||
#define PIOS_INCLUDE_GCSRCVR
|
||||
#define PIOS_INCLUDE_OPLINKRCVR
|
||||
|
||||
|
@ -132,12 +132,13 @@ static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
};
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
@ -498,6 +499,27 @@ void PIOS_Board_Init(void)
|
||||
case HWSETTINGS_RM_FLEXIPORT_OSDHK:
|
||||
PIOS_Board_configure_com(&pios_usart_hkosd_flexi_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_SRXL:
|
||||
#if defined(PIOS_INCLUDE_SRXL)
|
||||
{
|
||||
uint32_t pios_usart_srxl_id;
|
||||
if (PIOS_USART_Init(&pios_usart_srxl_id, &pios_usart_srxl_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_srxl_id;
|
||||
if (PIOS_SRXL_Init(&pios_srxl_id, &pios_usart_com_driver, pios_usart_srxl_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_srxl_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_srxl_rcvr_id, &pios_srxl_rcvr_driver, pios_srxl_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
} /* hwsettings_rm_flexiport */
|
||||
|
||||
/* Moved this here to allow binding on flexiport */
|
||||
@ -867,7 +889,6 @@ void PIOS_Board_Init(void)
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_GCSRCVR)
|
||||
GCSReceiverInitialize();
|
||||
uint32_t pios_gcsrcvr_id;
|
||||
@ -943,8 +964,18 @@ void PIOS_Board_Init(void)
|
||||
if (ws2811_pin_settings != HWSETTINGS_WS2811LED_OUT_DISABLED && ws2811_pin_settings < NELEMENTS(pios_ws2811_pin_cfg)) {
|
||||
PIOS_WS2811_Init(&pios_ws2811_cfg, &pios_ws2811_pin_cfg[ws2811_pin_settings]);
|
||||
}
|
||||
|
||||
#endif // PIOS_INCLUDE_WS2811
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
{
|
||||
uint8_t adc_config[HWSETTINGS_ADCROUTING_NUMELEM];
|
||||
HwSettingsADCRoutingArrayGet(adc_config);
|
||||
for (uint32_t i = 0; i < HWSETTINGS_ADCROUTING_NUMELEM; i++) {
|
||||
if (adc_config[i] != HWSETTINGS_ADCROUTING_DISABLED) {
|
||||
PIOS_ADC_PinSetup(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // PIOS_INCLUDE_ADC
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -257,6 +257,12 @@ extern uint32_t pios_packet_handler;
|
||||
#define PIOS_SBUS_MAX_DEVS 1
|
||||
#define PIOS_SBUS_NUM_INPUTS (16 + 2)
|
||||
|
||||
// -------------------------
|
||||
// Receiver Multiplex SRXL input
|
||||
// -------------------------
|
||||
#define PIOS_SRXL_MAX_DEVS 1
|
||||
#define PIOS_SRXL_NUM_INPUTS 16
|
||||
|
||||
// -------------------------
|
||||
// Receiver DSM input
|
||||
// -------------------------
|
||||
@ -281,23 +287,27 @@ extern uint32_t pios_packet_handler;
|
||||
// PIOS_ADC_PinGet(4) = VREF
|
||||
// PIOS_ADC_PinGet(5) = Temperature sensor
|
||||
// -------------------------
|
||||
#define PIOS_DMA_PIN_CONFIG \
|
||||
{ \
|
||||
{ GPIOC, GPIO_Pin_1, ADC_Channel_11 }, \
|
||||
{ GPIOC, GPIO_Pin_2, ADC_Channel_12 }, \
|
||||
{ NULL, 0, ADC_Channel_Vrefint }, /* Voltage reference */ \
|
||||
{ NULL, 0, ADC_Channel_TempSensor }, /* Temperature sensor */ \
|
||||
#define PIOS_DMA_PIN_CONFIG \
|
||||
{ \
|
||||
{ GPIOC, GPIO_Pin_1, ADC_Channel_11, false }, /* batt/sonar pin 3 */ \
|
||||
{ GPIOC, GPIO_Pin_2, ADC_Channel_12, false }, /* batt/sonar pin 4 */ \
|
||||
{ GPIOA, GPIO_Pin_3, ADC_Channel_3, false }, /* Servo pin 3 */ \
|
||||
{ GPIOA, GPIO_Pin_2, ADC_Channel_2, false }, /* Servo pin 4 */ \
|
||||
{ GPIOA, GPIO_Pin_1, ADC_Channel_1, false }, /* Servo pin 5 */ \
|
||||
{ GPIOA, GPIO_Pin_0, ADC_Channel_9, false }, /* Servo pin 6 */ \
|
||||
{ NULL, 0, ADC_Channel_Vrefint, false }, /* Voltage reference */ \
|
||||
{ NULL, 0, ADC_Channel_TempSensor, false }, /* Temperature sensor */ \
|
||||
}
|
||||
|
||||
/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */
|
||||
/* which is annoying because this then determines the rate at which we generate buffer turnover events */
|
||||
/* the objective here is to get enough buffer space to support 100Hz averaging rate */
|
||||
#define PIOS_ADC_NUM_CHANNELS 4
|
||||
#define PIOS_ADC_NUM_CHANNELS 8
|
||||
#define PIOS_ADC_MAX_OVERSAMPLING 2
|
||||
#define PIOS_ADC_USE_ADC2 0
|
||||
|
||||
#define PIOS_ADC_USE_TEMP_SENSOR
|
||||
#define PIOS_ADC_TEMPERATURE_PIN 3
|
||||
#define PIOS_ADC_TEMPERATURE_PIN 7
|
||||
|
||||
// -------------------------
|
||||
// USB
|
||||
|
@ -20,8 +20,9 @@
|
||||
# (all architectures)
|
||||
UAVOBJSRCFILENAMES =
|
||||
UAVOBJSRCFILENAMES += statusgrounddrive
|
||||
UAVOBJSRCFILENAMES += pidstatus
|
||||
UAVOBJSRCFILENAMES += statusvtolland
|
||||
UAVOBJSRCFILENAMES += statusvtolautotakeoff
|
||||
UAVOBJSRCFILENAMES += pidstatus
|
||||
UAVOBJSRCFILENAMES += vtolselftuningstats
|
||||
UAVOBJSRCFILENAMES += accelgyrosettings
|
||||
UAVOBJSRCFILENAMES += accessorydesired
|
||||
|
@ -122,12 +122,13 @@ static const struct pios_exti_cfg pios_exti_hmc5x83_cfg __exti_config = {
|
||||
};
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_cfg = {
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
@ -925,6 +926,17 @@ void PIOS_Board_Init(void)
|
||||
default:
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
{
|
||||
uint8_t adc_config[HWSETTINGS_ADCROUTING_NUMELEM];
|
||||
HwSettingsADCRoutingArrayGet(adc_config);
|
||||
for (uint32_t i = 0; i < HWSETTINGS_ADCROUTING_NUMELEM; i++) {
|
||||
if (adc_config[i] != HWSETTINGS_ADCROUTING_DISABLED) {
|
||||
PIOS_ADC_PinSetup(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // PIOS_INCLUDE_ADC
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -242,11 +242,11 @@ extern uint32_t pios_com_hkosd_id;
|
||||
// -------------------------
|
||||
#define PIOS_DMA_PIN_CONFIG \
|
||||
{ \
|
||||
{ GPIOC, GPIO_Pin_0, ADC_Channel_10 }, \
|
||||
{ GPIOC, GPIO_Pin_1, ADC_Channel_11 }, \
|
||||
{ NULL, 0, ADC_Channel_Vrefint }, /* Voltage reference */ \
|
||||
{ NULL, 0, ADC_Channel_TempSensor }, /* Temperature sensor */ \
|
||||
{ GPIOC, GPIO_Pin_2, ADC_Channel_12 } \
|
||||
{ GPIOC, GPIO_Pin_0, ADC_Channel_10, true }, \
|
||||
{ GPIOC, GPIO_Pin_1, ADC_Channel_11, true }, \
|
||||
{ NULL, 0, ADC_Channel_Vrefint, true }, /* Voltage reference */ \
|
||||
{ NULL, 0, ADC_Channel_TempSensor, true }, /* Temperature sensor */ \
|
||||
{ GPIOC, GPIO_Pin_2, ADC_Channel_12, true } \
|
||||
}
|
||||
|
||||
/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */
|
||||
|
@ -25,6 +25,7 @@
|
||||
|
||||
UAVOBJSRCFILENAMES =
|
||||
UAVOBJSRCFILENAMES += statusgrounddrive
|
||||
UAVOBJSRCFILENAMES += statusvtolautotakeoff
|
||||
UAVOBJSRCFILENAMES += pidstatus
|
||||
UAVOBJSRCFILENAMES += statusvtolland
|
||||
UAVOBJSRCFILENAMES += vtolselftuningstats
|
||||
|
@ -152,7 +152,7 @@ void PIOS_Board_Init(void)
|
||||
/* Configure IO ports */
|
||||
|
||||
/* Configure Telemetry port */
|
||||
uint8_t hwsettings_rv_telemetryport;
|
||||
HwSettingsRV_TelemetryPortOptions hwsettings_rv_telemetryport;
|
||||
HwSettingsRV_TelemetryPortGet(&hwsettings_rv_telemetryport);
|
||||
|
||||
switch (hwsettings_rv_telemetryport) {
|
||||
@ -164,10 +164,12 @@ void PIOS_Board_Init(void)
|
||||
case HWSETTINGS_RV_TELEMETRYPORT_COMAUX:
|
||||
PIOS_Board_configure_com(&pios_udp_telem_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_udp_com_driver, &pios_com_aux_id);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
} /* hwsettings_rv_telemetryport */
|
||||
|
||||
/* Configure GPS port */
|
||||
uint8_t hwsettings_rv_gpsport;
|
||||
HwSettingsRV_GPSPortOptions hwsettings_rv_gpsport;
|
||||
HwSettingsRV_GPSPortGet(&hwsettings_rv_gpsport);
|
||||
switch (hwsettings_rv_gpsport) {
|
||||
case HWSETTINGS_RV_GPSPORT_DISABLED:
|
||||
@ -184,10 +186,12 @@ void PIOS_Board_Init(void)
|
||||
case HWSETTINGS_RV_GPSPORT_COMAUX:
|
||||
PIOS_Board_configure_com(&pios_udp_gps_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_udp_com_driver, &pios_com_aux_id);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
} /* hwsettings_rv_gpsport */
|
||||
|
||||
/* Configure AUXPort */
|
||||
uint8_t hwsettings_rv_auxport;
|
||||
HwSettingsRV_AuxPortOptions hwsettings_rv_auxport;
|
||||
HwSettingsRV_AuxPortGet(&hwsettings_rv_auxport);
|
||||
|
||||
switch (hwsettings_rv_auxport) {
|
||||
@ -201,6 +205,7 @@ void PIOS_Board_Init(void)
|
||||
case HWSETTINGS_RV_AUXPORT_COMAUX:
|
||||
PIOS_Board_configure_com(&pios_udp_aux_cfg, PIOS_COM_AUX_RX_BUF_LEN, PIOS_COM_AUX_TX_BUF_LEN, &pios_udp_com_driver, &pios_com_aux_id);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
} /* hwsettings_rv_auxport */
|
||||
}
|
||||
|
@ -52,6 +52,8 @@ int32_t $(NAME)Initialize();
|
||||
UAVObjHandle $(NAME)Handle();
|
||||
void $(NAME)SetDefaults(UAVObjHandle obj, uint16_t instId);
|
||||
|
||||
$(DATAFIELDINFO)
|
||||
|
||||
$(DATASTRUCTURES)
|
||||
/*
|
||||
* Packed Object data (unaligned).
|
||||
@ -86,8 +88,6 @@ static inline int32_t $(NAME)GetMetadata(UAVObjMetadata *dataOut) { return UAVOb
|
||||
static inline int32_t $(NAME)SetMetadata(const UAVObjMetadata *dataIn) { return UAVObjSetMetadata($(NAME)Handle(), dataIn); }
|
||||
static inline int8_t $(NAME)ReadOnly() { return UAVObjReadOnly($(NAME)Handle()); }
|
||||
|
||||
$(DATAFIELDINFO)
|
||||
|
||||
/* Set/Get functions */
|
||||
$(SETGETFIELDSEXTERN)
|
||||
|
||||
|
@ -376,49 +376,48 @@ UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connectionHandle
|
||||
}
|
||||
|
||||
uint8_t processedBytes = (*position);
|
||||
uint8_t count = 0;
|
||||
|
||||
// stop processing as soon as a complete packet is received, error is encountered or buffer is processed entirely
|
||||
while ((count = length - (*position)) > 0
|
||||
while ((length > (*position))
|
||||
&& iproc->state != UAVTALK_STATE_COMPLETE
|
||||
&& iproc->state != UAVTALK_STATE_ERROR) {
|
||||
// Receive state machine
|
||||
if (iproc->state == UAVTALK_STATE_SYNC &&
|
||||
if ((length > (*position)) && iproc->state == UAVTALK_STATE_SYNC &&
|
||||
!UAVTalkProcess_SYNC(connection, iproc, rxbuffer, length, position)) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (iproc->state == UAVTALK_STATE_TYPE &&
|
||||
if ((length > (*position)) && iproc->state == UAVTALK_STATE_TYPE &&
|
||||
!UAVTalkProcess_TYPE(connection, iproc, rxbuffer, length, position)) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (iproc->state == UAVTALK_STATE_SIZE &&
|
||||
if ((length > (*position)) && iproc->state == UAVTALK_STATE_SIZE &&
|
||||
!UAVTalkProcess_SIZE(connection, iproc, rxbuffer, length, position)) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (iproc->state == UAVTALK_STATE_OBJID &&
|
||||
if ((length > (*position)) && iproc->state == UAVTALK_STATE_OBJID &&
|
||||
!UAVTalkProcess_OBJID(connection, iproc, rxbuffer, length, position)) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (iproc->state == UAVTALK_STATE_INSTID &&
|
||||
if ((length > (*position)) && iproc->state == UAVTALK_STATE_INSTID &&
|
||||
!UAVTalkProcess_INSTID(connection, iproc, rxbuffer, length, position)) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (iproc->state == UAVTALK_STATE_TIMESTAMP &&
|
||||
if ((length > (*position)) && iproc->state == UAVTALK_STATE_TIMESTAMP &&
|
||||
!UAVTalkProcess_TIMESTAMP(connection, iproc, rxbuffer, length, position)) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (iproc->state == UAVTALK_STATE_DATA &&
|
||||
if ((length > (*position)) && iproc->state == UAVTALK_STATE_DATA &&
|
||||
!UAVTalkProcess_DATA(connection, iproc, rxbuffer, length, position)) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (iproc->state == UAVTALK_STATE_CS &&
|
||||
if ((length > (*position)) && iproc->state == UAVTALK_STATE_CS &&
|
||||
!UAVTalkProcess_CS(connection, iproc, rxbuffer, length, position)) {
|
||||
break;
|
||||
}
|
||||
|
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
@ -245,8 +245,7 @@ Item {
|
||||
visible: SystemAlarms.Alarm_PathPlan == 1
|
||||
|
||||
Text {
|
||||
text: ["FLY END POINT","FLY VECTOR","FLY CIRCLE RIGHT","FLY CIRCLE LEFT","DRIVE END POINT","DRIVE VECTOR","DRIVE CIRCLE LEFT",
|
||||
"DRIVE CIRCLE RIGHT","FIXED ATTITUDE","SET ACCESSORY","LAND","DISARM ALARM"][PathDesired.Mode]
|
||||
text: ["GOTO ENDPOINT","FOLLOW VECTOR","CIRCLE RIGHT","CIRCLE LEFT","FIXED ATTITUDE","SET ACCESSORY","DISARM ALARM","LAND","BRAKE","VELOCITY","AUTO TAKEOFF"][PathDesired.Mode]
|
||||
anchors.centerIn: parent
|
||||
color: "cyan"
|
||||
|
||||
@ -355,6 +354,13 @@ Item {
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
|
||||
MouseArea {
|
||||
id: reset_consumed_energy_mouseArea;
|
||||
anchors.fill: parent;
|
||||
cursorShape: Qt.PointingHandCursor;
|
||||
onClicked: qmlWidget.resetConsumedEnergy();
|
||||
}
|
||||
|
||||
// Alarm based on FlightBatteryState.EstimatedFlightTime < 120s orange, < 60s red
|
||||
color: (FlightBatteryState.EstimatedFlightTime <= 120 && FlightBatteryState.EstimatedFlightTime > 60 ? "orange" :
|
||||
(FlightBatteryState.EstimatedFlightTime <= 60 ? "red": info.batColors[SystemAlarms.Alarm_Battery]))
|
||||
|
@ -480,6 +480,13 @@ Item {
|
||||
Rectangle {
|
||||
anchors.fill: parent
|
||||
|
||||
MouseArea {
|
||||
id: reset_panel_consumed_energy_mouseArea;
|
||||
anchors.fill: parent;
|
||||
cursorShape: Qt.PointingHandCursor;
|
||||
onClicked: qmlWidget.resetConsumedEnergy();
|
||||
}
|
||||
|
||||
// Alarm based on FlightBatteryState.EstimatedFlightTime < 120s orange, < 60s red
|
||||
color: (FlightBatteryState.EstimatedFlightTime <= 120 && FlightBatteryState.EstimatedFlightTime > 60 ? "orange" :
|
||||
(FlightBatteryState.EstimatedFlightTime <= 60 ? "red": panels.batColors[SystemAlarms.Alarm_Battery]))
|
||||
@ -526,6 +533,13 @@ Item {
|
||||
anchors.fill: parent
|
||||
//color: panels.batColors[SystemAlarms.Alarm_Battery]
|
||||
|
||||
MouseArea {
|
||||
id: reset_panel_consumed_energy_mouseArea2;
|
||||
anchors.fill: parent;
|
||||
cursorShape: Qt.PointingHandCursor;
|
||||
onClicked: qmlWidget.resetConsumedEnergy();
|
||||
}
|
||||
|
||||
// Alarm based on FlightBatteryState.EstimatedFlightTime < 120s orange, < 60s red
|
||||
color: (FlightBatteryState.EstimatedFlightTime <= 120 && FlightBatteryState.EstimatedFlightTime > 60 ? "orange" :
|
||||
(FlightBatteryState.EstimatedFlightTime <= 60 ? "red": panels.batColors[SystemAlarms.Alarm_Battery]))
|
||||
|
@ -125,7 +125,7 @@
|
||||
<message>
|
||||
<location/>
|
||||
<source>Contribute usage statistics:</source>
|
||||
<translation type="unfinished">Contribuer aux statistiques d'utilisation :</translation>
|
||||
<translation>Contribuer aux statistiques d'utilisation :</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location/>
|
||||
@ -10712,7 +10712,7 @@ Voulez-vous toujours continuer ?</translation>
|
||||
<context>
|
||||
<name>ConfigInputWidget</name>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/config/configinputwidget.cpp" line="+393"/>
|
||||
<location filename="../../../src/plugins/config/configinputwidget.cpp" line="+396"/>
|
||||
<source>http://wiki.openpilot.org/x/04Cf</source>
|
||||
<translation></translation>
|
||||
</message>
|
||||
@ -10837,6 +10837,31 @@ Vous pouvez appuyer à tout moment sur 'Précédent' pour revenir à l
|
||||
<translatorcomment>Dérive / gouvernail ?</translatorcomment>
|
||||
<translation>Pour un Quadricoptère : Profondeur correspond à la Rotation Avant, Ailerons à Roulis et Dérive correspond à Lacet.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+209"/>
|
||||
<source><p>Please enable throttle hold mode.</p><p>Move the Collective Pitch stick.</p></source>
|
||||
<translation><p>Veuillez activer les gaz en position maintenue.</p><p>Bougez le manche du Collectif de tangage.</p></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+3"/>
|
||||
<source><p>Please toggle the Flight Mode switch.</p><p>For switches you may have to repeat this rapidly.</p><p>Alternatively, you can click Next to skip this channel, but you will get only <b>ONE</b> Flight Mode.</p></source>
|
||||
<translation><p>Veuillez activer l'interrupteur de Mode de Vol.</p><p>Pour les interrupteurs vous pourriez avoir à répéter l'opération rapidement.</p><p>Vous avez la possibilité d'appuyer sur Suivant pour ignorer ce canal mais vous aurez seulement <b>UN</b> Mode de Vol.</p></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+5"/>
|
||||
<source><p>Please disable throttle hold mode.</p><p>Move the Throttle stick.</p></source>
|
||||
<translation><p>Veuillez désactiver les gaz en position maintenue.</p><p>Bougez le manche des Gaz.</p></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+3"/>
|
||||
<source><p>Please move each control one at a time according to the instructions and picture below.</p><p>Move the %1 stick.</p></source>
|
||||
<translation><p>Veuillez bouger chaque organe de contrôle, un seul à la fois, en fonction des instructions et de l'image ci-dessous.</p><p>Bougez le manche %1.</p></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+5"/>
|
||||
<source><p>Alternatively, click Next to skip this channel.</p></source>
|
||||
<translation><p>Vous avez la possibilité d'appuyer sur Suivant pour ignorer ce canal.</p></translation>
|
||||
</message>
|
||||
<message>
|
||||
<source>Please center all controls and trims and press Next when ready.
|
||||
|
||||
@ -10867,7 +10892,7 @@ IMPORTANT: These new settings have not been saved to the board yet. After pressi
|
||||
IMPORTANT : Ces nouveaux paramètres ne sont pas encore enregistrés sur la carte. Après avoir appuyé sur Suivant vous serez dirigé vers l'onglet Paramètres d'Armement où vous pourrez choisir votre séquence d'armement et enregistrer la configuration.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+23"/>
|
||||
<location line="-202"/>
|
||||
<source>Please center all controls and trims and press Next when ready.
|
||||
|
||||
For a ground vehicle, this center position will be used as neutral value of each channel.</source>
|
||||
@ -10876,52 +10901,47 @@ For a ground vehicle, this center position will be used as neutral value of each
|
||||
Pour un véhicule terrestre, ces positions centrales seront utilisées comme neutre de chaque canal.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+178"/>
|
||||
<source>Please enable throttle hold mode.
|
||||
|
||||
Move the Collective Pitch stick.</source>
|
||||
<translatorcomment>hélico ? à traduire [Platypus] Ca convient ? [soh] A confirmer par un héliqueux.</translatorcomment>
|
||||
<translation type="unfinished">Veuillez activer les gaz en position maintenue.
|
||||
<translation type="obsolete">Veuillez activer les gaz en position maintenue.
|
||||
|
||||
Bougez le manche du Collectif de tangage.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+2"/>
|
||||
<source>Please toggle the Flight Mode switch.
|
||||
|
||||
For switches you may have to repeat this rapidly.</source>
|
||||
<translation>Veuillez activer l'interrupteur de Mode de Vol.
|
||||
<translation type="vanished">Veuillez activer l'interrupteur de Mode de Vol.
|
||||
|
||||
Pour les interrupteurs vous pourriez avoir à répéter l'opération rapidement.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+2"/>
|
||||
<source>Please disable throttle hold mode.
|
||||
|
||||
Move the Throttle stick.</source>
|
||||
<translatorcomment>hélico ? à traduire</translatorcomment>
|
||||
<translation type="unfinished">Veuillez désactiver les gaz en position maintenue.
|
||||
<translation type="obsolete">Veuillez désactiver les gaz en position maintenue.
|
||||
|
||||
Bougez le manche des Gaz.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+2"/>
|
||||
<source>Please move each control one at a time according to the instructions and picture below.
|
||||
|
||||
Move the %1 stick.</source>
|
||||
<translation>Veuillez bouger chaque organe de contrôle, un seul à la fois, en fonction des instructions et de l'image ci-dessous.
|
||||
<translation type="vanished">Veuillez bouger chaque organe de contrôle, un seul à la fois, en fonction des instructions et de l'image ci-dessous.
|
||||
|
||||
Bougez le manche %1.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+6"/>
|
||||
<location line="+208"/>
|
||||
<source>Next / Skip</source>
|
||||
<translation>Suivant / Sauter</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+1"/>
|
||||
<source> Alternatively, click Next to skip this channel.</source>
|
||||
<translation> Vous avez la possibilité d'appuyer sur Suivant pour ignorer ce canal.</translation>
|
||||
<translation type="vanished"> Vous avez la possibilité d'appuyer sur Suivant pour ignorer ce canal.</translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+748"/>
|
||||
@ -16187,69 +16207,87 @@ IMPORTANT : Ces nouveaux paramètres ne sont pas encore enregistrés sur la cart
|
||||
<name>ConfigCcpmWidget</name>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp" line="+1080"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+1110"/>
|
||||
<source><h1>Swashplate Leveling Routine</h1></source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+1"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+1"/>
|
||||
<source><b>You are about to start the Swashplate levelling routine.</b><p>This process will start by downloading the current configuration from the GCS to the OP hardware and will adjust your configuration at various stages.<p>The final state of your system should match the current configuration in the GCS config gadget.</p><p>Please ensure all ccpm settings in the GCS are correct before continuing.</p><p>If this process is interrupted, then the state of your OP board may not match the GCS configuration.</p><p><i>After completing this process, please check all settings before attempting to fly.</i></p><p><font color=red><b>Please disconnect your motor to ensure it will not spin up.</b></font><p><hr><i>Do you wish to proceed?</i></p></source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+128"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+128"/>
|
||||
<source><h2>Neutral levelling</h2><p>Using adjustment of:<ul><li>Servo horns,</li><li>Link lengths,</li><li>Neutral triming spinboxes to the right</li></ul><br>Ensure that the swashplate is in the center of desired travel range and is level.</source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+14"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+14"/>
|
||||
<source><h2>Max levelling</h2><p>Using adjustment of:<ul><li>Max triming spinboxes to the right ONLY</li></ul><br>Ensure that the swashplate is at the top of desired travel range and is level.</source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+13"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+13"/>
|
||||
<source><h2>Min levelling</h2><p>Using adjustment of:<ul><li>Min triming spinboxes to the right ONLY</li></ul><br>Ensure that the swashplate is at the bottom of desired travel range and is level.</source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+19"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+19"/>
|
||||
<source><h2>Levelling verification</h2><p>Adjust the slider to the right over it's full range and observe the swashplate motion. It should remain level over the entire range of travel.</p></source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+7"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+7"/>
|
||||
<source><h2>Levelling complete</h2><p>Press the Finish button to save these settings to the SD card</p><p>Press the cancel button to return to the pre-levelling settings</p></source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+68"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+68"/>
|
||||
<source><h2>Levelling Cancelled</h2><p>Previous settings have been restored.</source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+43"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+43"/>
|
||||
<source><h2>Levelling Completed</h2><p>New settings have been saved to the SD card</source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+12"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+12"/>
|
||||
<source><font color=red><h1>Warning!!!</h2></font></source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+6"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+6"/>
|
||||
<source><h2>This code has many configurations.</h2><p>Please double check all settings before attempting flight!</source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+11"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+11"/>
|
||||
<source><h2>The CCPM mixer code needs more testing!</h2><p><font color=red>Use it at your own risk!</font><p>Do you wish to continue?</source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location line="+16"/>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+16"/>
|
||||
<source><h2>The CCPM swashplate levelling code is NOT complete!</h2><p><font color=red>DO NOT use it for flight!</font></source>
|
||||
<translation type="unfinished"></translation>
|
||||
</message>
|
||||
<message>
|
||||
<location filename="../../../src/plugins/config/cfg_vehicletypes/configccpmwidget_dev.cpp" line="+174"/>
|
||||
<source>Channel already used</source>
|
||||
<translation type="unfinished">Canal déjà utilisé</translation>
|
||||
</message>
|
||||
</context>
|
||||
<context>
|
||||
<name>VehicleTemplateSelectorWidget</name>
|
||||
|
@ -115,6 +115,17 @@ $(INITFIELDS)
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns a new instance of this UAVDataObject with default field
|
||||
* values. This is intended to be used by 'reset to default' functionality.
|
||||
*
|
||||
* @return new instance of this class with default values.
|
||||
*/
|
||||
@Override
|
||||
public UAVDataObject getDefaultInstance(){
|
||||
return new $(NAME)();
|
||||
}
|
||||
|
||||
/**
|
||||
* Static function to retrieve an instance of the object.
|
||||
*/
|
||||
|
@ -158,6 +158,9 @@ void InputChannelForm::groupUpdated()
|
||||
case ManualControlSettings::CHANNELGROUPS_SBUS:
|
||||
count = 18;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELGROUPS_SRXL:
|
||||
count = 16;
|
||||
break;
|
||||
case ManualControlSettings::CHANNELGROUPS_GCS:
|
||||
count = GCSReceiver::CHANNEL_NUMELEM;
|
||||
break;
|
||||
|
@ -90,6 +90,7 @@ modelMapProxy::overlayType modelMapProxy::overlayTranslate(int type)
|
||||
case MapDataDelegate::MODE_FOLLOWVECTOR:
|
||||
case MapDataDelegate::MODE_VELOCITY:
|
||||
case MapDataDelegate::MODE_LAND:
|
||||
case MapDataDelegate::MODE_AUTOTAKEOFF:
|
||||
case MapDataDelegate::MODE_BRAKE:
|
||||
return OVERLAY_LINE;
|
||||
|
||||
|
@ -114,6 +114,7 @@ void MapDataDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanDa
|
||||
combo->addItem("Set Accessory", MODE_SETACCESSORY);
|
||||
combo->addItem("Disarm Alarm", MODE_DISARMALARM);
|
||||
combo->addItem("Land", MODE_LAND);
|
||||
combo->addItem("AutoTakeoff", MODE_AUTOTAKEOFF);
|
||||
combo->addItem("Brake", MODE_BRAKE);
|
||||
combo->addItem("Velocity", MODE_VELOCITY);
|
||||
|
||||
|
@ -31,19 +31,19 @@
|
||||
#include <QComboBox>
|
||||
#include "flightdatamodel.h"
|
||||
|
||||
|
||||
class MapDataDelegate : public QItemDelegate {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
typedef enum { MODE_GOTOENDPOINT = 0, MODE_FOLLOWVECTOR = 1, MODE_CIRCLERIGHT = 2, MODE_CIRCLELEFT = 3,
|
||||
MODE_FIXEDATTITUDE = 8, MODE_SETACCESSORY = 9, MODE_DISARMALARM = 10, MODE_LAND = 11,
|
||||
MODE_BRAKE = 12, MODE_VELOCITY = 13 } ModeOptions;
|
||||
MODE_FIXEDATTITUDE = 4, MODE_SETACCESSORY = 5, MODE_DISARMALARM = 6, MODE_LAND = 7,
|
||||
MODE_BRAKE = 8, MODE_VELOCITY = 9, MODE_AUTOTAKEOFF = 10 } ModeOptions;
|
||||
|
||||
typedef enum { ENDCONDITION_NONE = 0, ENDCONDITION_TIMEOUT = 1, ENDCONDITION_DISTANCETOTARGET = 2,
|
||||
ENDCONDITION_LEGREMAINING = 3, ENDCONDITION_BELOWERROR = 4, ENDCONDITION_ABOVEALTITUDE = 5,
|
||||
ENDCONDITION_ABOVESPEED = 6, ENDCONDITION_POINTINGTOWARDSNEXT = 7, ENDCONDITION_PYTHONSCRIPT = 8,
|
||||
ENDCONDITION_IMMEDIATE = 9 } EndConditionOptions;
|
||||
|
||||
typedef enum { COMMAND_ONCONDITIONNEXTWAYPOINT = 0, COMMAND_ONNOTCONDITIONNEXTWAYPOINT = 1,
|
||||
COMMAND_ONCONDITIONJUMPWAYPOINT = 2, COMMAND_ONNOTCONDITIONJUMPWAYPOINT = 3,
|
||||
COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT = 4 } CommandOptions;
|
||||
|
@ -18,6 +18,7 @@
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "uavobject.h"
|
||||
#include "flightbatterysettings.h"
|
||||
#include "utils/svgimageprovider.h"
|
||||
#ifdef USE_OSG
|
||||
#include "osgearth.h"
|
||||
@ -81,6 +82,8 @@ PfdQmlGadgetWidget::PfdQmlGadgetWidget(QWindow *parent) :
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
m_uavoManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(m_uavoManager);
|
||||
|
||||
foreach(const QString &objectName, objectsToExport) {
|
||||
UAVObject *object = objManager->getObject(objectName);
|
||||
@ -124,6 +127,14 @@ void PfdQmlGadgetWidget::setQmlFile(QString fn)
|
||||
}
|
||||
}
|
||||
|
||||
void PfdQmlGadgetWidget::resetConsumedEnergy()
|
||||
{
|
||||
FlightBatterySettings *mBatterySettings = FlightBatterySettings::GetInstance(m_uavoManager);
|
||||
|
||||
mBatterySettings->setResetConsumedEnergy(true);
|
||||
mBatterySettings->setData(mBatterySettings->getData());
|
||||
}
|
||||
|
||||
void PfdQmlGadgetWidget::setEarthFile(QString arg)
|
||||
{
|
||||
if (m_earthFile != arg) {
|
||||
|
@ -18,6 +18,7 @@
|
||||
#define PFDQMLGADGETWIDGET_H_
|
||||
|
||||
#include "pfdqmlgadgetconfiguration.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include <QQuickView>
|
||||
|
||||
class PfdQmlGadgetWidget : public QQuickView {
|
||||
@ -84,6 +85,8 @@ public:
|
||||
return m_altitude;
|
||||
}
|
||||
|
||||
Q_INVOKABLE void resetConsumedEnergy();
|
||||
|
||||
public slots:
|
||||
void setEarthFile(QString arg);
|
||||
void setTerrainEnabled(bool arg);
|
||||
@ -119,6 +122,7 @@ protected:
|
||||
void mouseReleaseEvent(QMouseEvent *event);
|
||||
|
||||
private:
|
||||
UAVObjectManager *m_uavoManager;
|
||||
QString m_qmlFileName;
|
||||
QString m_earthFile;
|
||||
bool m_openGLEnabled;
|
||||
|
@ -28,6 +28,7 @@ OTHER_FILES += UAVObjects.pluginspec
|
||||
# Add in all of the synthetic/generated uavobject files
|
||||
HEADERS += \
|
||||
$$UAVOBJECT_SYNTHETICS/statusgrounddrive.h \
|
||||
$$UAVOBJECT_SYNTHETICS/statusvtolautotakeoff.h \
|
||||
$$UAVOBJECT_SYNTHETICS/pidstatus.h \
|
||||
$$UAVOBJECT_SYNTHETICS/statusvtolland.h \
|
||||
$$UAVOBJECT_SYNTHETICS/vtolselftuningstats.h \
|
||||
@ -138,6 +139,7 @@ HEADERS += \
|
||||
|
||||
SOURCES += \
|
||||
$$UAVOBJECT_SYNTHETICS/statusgrounddrive.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/statusvtolautotakeoff.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/pidstatus.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/statusvtolland.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/vtolselftuningstats.cpp \
|
||||
|
@ -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.4.0/Tools/mingw491_32/opt/bin
|
||||
PYTHON_DIR = qt-5.4.1/Tools/mingw491_32/opt/bin
|
||||
|
||||
# Search the python using environment override first
|
||||
OPENPILOT_TOOLS_DIR = $$(OPENPILOT_TOOLS_DIR)
|
||||
|
@ -68,8 +68,8 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser *parser, QString templat
|
||||
// Write the flight object inialization files
|
||||
flightInitTemplate.replace(QString("$(OBJINC)"), objInc);
|
||||
flightInitTemplate.replace(QString("$(OBJINIT)"), flightObjInit);
|
||||
bool res = writeFileIfDiffrent(flightOutputPath.absolutePath() + "/uavobjectsinit.c",
|
||||
flightInitTemplate);
|
||||
bool res = writeFileIfDifferent(flightOutputPath.absolutePath() + "/uavobjectsinit.c",
|
||||
flightInitTemplate);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write flight object init file" << endl;
|
||||
return false;
|
||||
@ -77,8 +77,8 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser *parser, QString templat
|
||||
|
||||
// Write the flight object initialization header
|
||||
flightInitIncludeTemplate.replace(QString("$(SIZECALCULATION)"), QString().setNum(sizeCalc));
|
||||
res = writeFileIfDiffrent(flightOutputPath.absolutePath() + "/uavobjectsinit.h",
|
||||
flightInitIncludeTemplate);
|
||||
res = writeFileIfDifferent(flightOutputPath.absolutePath() + "/uavobjectsinit.h",
|
||||
flightInitIncludeTemplate);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write flight object init header file" << endl;
|
||||
return false;
|
||||
@ -87,8 +87,8 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser *parser, QString templat
|
||||
// Write the flight object Makefile
|
||||
flightMakeTemplate.replace(QString("$(UAVOBJFILENAMES)"), objFileNames);
|
||||
flightMakeTemplate.replace(QString("$(UAVOBJNAMES)"), objNames);
|
||||
res = writeFileIfDiffrent(flightOutputPath.absolutePath() + "/Makefile.inc",
|
||||
flightMakeTemplate);
|
||||
res = writeFileIfDifferent(flightOutputPath.absolutePath() + "/Makefile.inc",
|
||||
flightMakeTemplate);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write flight Makefile" << endl;
|
||||
return false;
|
||||
@ -115,13 +115,25 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo *info)
|
||||
replaceCommonTags(outInclude, info);
|
||||
replaceCommonTags(outCode, info);
|
||||
|
||||
// Use the appropriate typedef for enums where we find them. Set up
|
||||
// that StringList here for use below.
|
||||
//
|
||||
QStringList typeList;
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
if (info->fields[n]->type == FIELDTYPE_ENUM) {
|
||||
typeList << QString("%1%2Options").arg(info->name).arg(info->fields[n]->name);
|
||||
} else {
|
||||
typeList << fieldTypeStrC[info->fields[n]->type];
|
||||
}
|
||||
}
|
||||
|
||||
// Replace the $(DATAFIELDS) tag
|
||||
QString type;
|
||||
QString fields;
|
||||
QString dataStructures;
|
||||
for (int n = 0; n < info->fields.length(); ++n) {
|
||||
// Determine type
|
||||
type = fieldTypeStrC[info->fields[n]->type];
|
||||
type = typeList[n];
|
||||
// Append field
|
||||
// Check if it a named set and creates structures accordingly
|
||||
if (info->fields[n]->numElements > 1) {
|
||||
@ -158,7 +170,7 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo *info)
|
||||
// Only for enum types
|
||||
if (info->fields[n]->type == FIELDTYPE_ENUM) {
|
||||
enums.append(QString("\n// Enumeration options for field %1\n").arg(info->fields[n]->name));
|
||||
enums.append("typedef enum {\n");
|
||||
enums.append("typedef enum __attribute__ ((__packed__)) {\n");
|
||||
// Go through each option
|
||||
QStringList options = info->fields[n]->options;
|
||||
for (int m = 0; m < options.length(); ++m) {
|
||||
@ -262,26 +274,26 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo *info)
|
||||
if (info->fields[n]->numElements == 1) {
|
||||
/* Set */
|
||||
setgetfields.append(QString("void %2%3Set(%1 *New%3)\n")
|
||||
.arg(fieldTypeStrC[info->fields[n]->type])
|
||||
.arg(typeList[n])
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name));
|
||||
setgetfields.append(QString("{\n"));
|
||||
setgetfields.append(QString(" UAVObjSetDataField(%1Handle(), (void *)New%2, offsetof(%1Data, %2), sizeof(%3));\n")
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(fieldTypeStrC[info->fields[n]->type]));
|
||||
.arg(typeList[n]));
|
||||
setgetfields.append(QString("}\n"));
|
||||
|
||||
/* GET */
|
||||
setgetfields.append(QString("void %2%3Get(%1 *New%3)\n")
|
||||
.arg(fieldTypeStrC[info->fields[n]->type])
|
||||
.arg(typeList[n])
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name));
|
||||
setgetfields.append(QString("{\n"));
|
||||
setgetfields.append(QString(" UAVObjGetDataField(%1Handle(), (void *)New%2, offsetof(%1Data, %2), sizeof(%3));\n")
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(fieldTypeStrC[info->fields[n]->type]));
|
||||
.arg(typeList[n]));
|
||||
setgetfields.append(QString("}\n"));
|
||||
} else {
|
||||
// When no struct accessor is available for a field array accessor is the default.
|
||||
@ -300,7 +312,7 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo *info)
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(info->fields[n]->numElements)
|
||||
.arg(fieldTypeStrC[info->fields[n]->type]));
|
||||
.arg(typeList[n]));
|
||||
setgetfields.append(QString("}\n"));
|
||||
|
||||
/* GET */
|
||||
@ -313,7 +325,7 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo *info)
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(info->fields[n]->numElements)
|
||||
.arg(fieldTypeStrC[info->fields[n]->type]));
|
||||
.arg(typeList[n]));
|
||||
setgetfields.append(QString("}\n"));
|
||||
|
||||
// Append array suffix to array accessors
|
||||
@ -323,7 +335,7 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo *info)
|
||||
// array based field accessor
|
||||
/* SET */
|
||||
setgetfields.append(QString("void %2%3%4Set( %1 *New%3 )\n")
|
||||
.arg(fieldTypeStrC[info->fields[n]->type])
|
||||
.arg(typeList[n])
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(suffix));
|
||||
@ -332,12 +344,12 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo *info)
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(info->fields[n]->numElements)
|
||||
.arg(fieldTypeStrC[info->fields[n]->type]));
|
||||
.arg(typeList[n]));
|
||||
setgetfields.append(QString("}\n"));
|
||||
|
||||
/* GET */
|
||||
setgetfields.append(QString("void %2%3%4Get( %1 *New%3 )\n")
|
||||
.arg(fieldTypeStrC[info->fields[n]->type])
|
||||
.arg(typeList[n])
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(suffix));
|
||||
@ -346,7 +358,7 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo *info)
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(info->fields[n]->numElements)
|
||||
.arg(fieldTypeStrC[info->fields[n]->type]));
|
||||
.arg(typeList[n]));
|
||||
setgetfields.append(QString("}\n"));
|
||||
}
|
||||
}
|
||||
@ -378,14 +390,14 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo *info)
|
||||
}
|
||||
/* SET */
|
||||
setgetfieldsextern.append(QString("extern void %2%3%4Set(%1 *New%3);\n")
|
||||
.arg(fieldTypeStrC[info->fields[n]->type])
|
||||
.arg(typeList[n])
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(suffix));
|
||||
|
||||
/* GET */
|
||||
setgetfieldsextern.append(QString("extern void %2%3%4Get(%1 *New%3);\n")
|
||||
.arg(fieldTypeStrC[info->fields[n]->type])
|
||||
.arg(typeList[n])
|
||||
.arg(info->name)
|
||||
.arg(info->fields[n]->name)
|
||||
.arg(suffix));
|
||||
@ -394,13 +406,13 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo *info)
|
||||
outInclude.replace(QString("$(SETGETFIELDSEXTERN)"), setgetfieldsextern);
|
||||
|
||||
// Write the flight code
|
||||
bool res = writeFileIfDiffrent(flightOutputPath.absolutePath() + "/" + info->namelc + ".c", outCode);
|
||||
bool res = writeFileIfDifferent(flightOutputPath.absolutePath() + "/" + info->namelc + ".c", outCode);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write flight code files" << endl;
|
||||
return false;
|
||||
}
|
||||
|
||||
res = writeFileIfDiffrent(flightOutputPath.absolutePath() + "/" + info->namelc + ".h", outInclude);
|
||||
res = writeFileIfDifferent(flightOutputPath.absolutePath() + "/" + info->namelc + ".h", outInclude);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write flight include files" << endl;
|
||||
return false;
|
||||
|
@ -62,7 +62,7 @@ bool UAVObjectGeneratorGCS::generate(UAVObjectParser *parser, QString templatepa
|
||||
// Write the gcs object inialization files
|
||||
gcsInitTemplate.replace(QString("$(OBJINC)"), objInc);
|
||||
gcsInitTemplate.replace(QString("$(OBJINIT)"), gcsObjInit);
|
||||
bool res = writeFileIfDiffrent(gcsOutputPath.absolutePath() + "/uavobjectsinit.cpp", gcsInitTemplate);
|
||||
bool res = writeFileIfDifferent(gcsOutputPath.absolutePath() + "/uavobjectsinit.cpp", gcsInitTemplate);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write output files" << endl;
|
||||
return false;
|
||||
@ -371,12 +371,12 @@ bool UAVObjectGeneratorGCS::process_object(ObjectInfo *info)
|
||||
outCode.replace(QString("$(INITFIELDS)"), initfields);
|
||||
|
||||
// Write the GCS code
|
||||
bool res = writeFileIfDiffrent(gcsOutputPath.absolutePath() + "/" + info->namelc + ".cpp", outCode);
|
||||
bool res = writeFileIfDifferent(gcsOutputPath.absolutePath() + "/" + info->namelc + ".cpp", outCode);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write gcs output files" << endl;
|
||||
return false;
|
||||
}
|
||||
res = writeFileIfDiffrent(gcsOutputPath.absolutePath() + "/" + info->namelc + ".h", outInclude);
|
||||
res = writeFileIfDifferent(gcsOutputPath.absolutePath() + "/" + info->namelc + ".h", outInclude);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write gcs output files" << endl;
|
||||
return false;
|
||||
|
@ -75,7 +75,7 @@ bool writeFile(QString name, QString & str)
|
||||
/**
|
||||
* Write contents of string to file if the content changes
|
||||
*/
|
||||
bool writeFileIfDiffrent(QString name, QString & str)
|
||||
bool writeFileIfDifferent(QString name, QString & str)
|
||||
{
|
||||
if (str == readFile(name, false)) {
|
||||
return true;
|
||||
|
@ -37,6 +37,6 @@
|
||||
QString readFile(QString name);
|
||||
QString readFile(QString name);
|
||||
bool writeFile(QString name, QString & str);
|
||||
bool writeFileIfDiffrent(QString name, QString & str);
|
||||
bool writeFileIfDifferent(QString name, QString & str);
|
||||
|
||||
#endif
|
||||
|
@ -62,7 +62,7 @@ bool UAVObjectGeneratorJava::generate(UAVObjectParser *parser, QString templatep
|
||||
// Write the gcs object inialization files
|
||||
javaInitTemplate.replace(QString("$(OBJINC)"), objInc);
|
||||
javaInitTemplate.replace(QString("$(OBJINIT)"), javaObjInit);
|
||||
bool res = writeFileIfDiffrent(javaOutputPath.absolutePath() + "/UAVObjectsInitialize.java", javaInitTemplate);
|
||||
bool res = writeFileIfDifferent(javaOutputPath.absolutePath() + "/UAVObjectsInitialize.java", javaInitTemplate);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write output files" << endl;
|
||||
return false;
|
||||
@ -238,7 +238,7 @@ bool UAVObjectGeneratorJava::process_object(ObjectInfo *info)
|
||||
outCode.replace(QString("$(INITFIELDS)"), initfields);
|
||||
|
||||
// Write the java code
|
||||
bool res = writeFileIfDiffrent(javaOutputPath.absolutePath() + "/" + info->name + ".java", outCode);
|
||||
bool res = writeFileIfDifferent(javaOutputPath.absolutePath() + "/" + info->name + ".java", outCode);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write gcs output files" << endl;
|
||||
return false;
|
||||
|
@ -110,7 +110,7 @@ bool UAVObjectGeneratorPython::process_object(ObjectInfo *info)
|
||||
outCode.replace(QString("$(DATAFIELDINIT)"), fields);
|
||||
|
||||
// Write the Python code
|
||||
bool res = writeFileIfDiffrent(pythonOutputPath.absolutePath() + "/" + info->namelc + ".py", outCode);
|
||||
bool res = writeFileIfDifferent(pythonOutputPath.absolutePath() + "/" + info->namelc + ".py", outCode);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write Python output files" << endl;
|
||||
return false;
|
||||
|
@ -93,8 +93,8 @@ bool UAVObjectGeneratorWireshark::generate(UAVObjectParser *parser, QString temp
|
||||
|
||||
/* Write the uavobject dissector's Makefile.common */
|
||||
wiresharkMakeTemplate.replace(QString("$(UAVOBJFILENAMES)"), objFileNames);
|
||||
bool res = writeFileIfDiffrent(uavobjectsOutputPath.absolutePath() + "/Makefile.common",
|
||||
wiresharkMakeTemplate);
|
||||
bool res = writeFileIfDifferent(uavobjectsOutputPath.absolutePath() + "/Makefile.common",
|
||||
wiresharkMakeTemplate);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write wireshark Makefile" << endl;
|
||||
return false;
|
||||
@ -279,7 +279,7 @@ bool UAVObjectGeneratorWireshark::process_object(ObjectInfo *info, QDir outputpa
|
||||
outCode.replace(QString("$(HEADERFIELDS)"), headerfields);
|
||||
|
||||
// Write the flight code
|
||||
bool res = writeFileIfDiffrent(outputpath.absolutePath() + "/packet-op-uavobjects-" + info->namelc + ".c", outCode);
|
||||
bool res = writeFileIfDifferent(outputpath.absolutePath() + "/packet-op-uavobjects-" + info->namelc + ".c", outCode);
|
||||
if (!res) {
|
||||
cout << "Error: Could not write wireshark code files" << endl;
|
||||
return false;
|
||||
|
@ -25,6 +25,8 @@
|
||||
*/
|
||||
|
||||
#include "uavobjectparser.h"
|
||||
#include <QDomDocument>
|
||||
#include <QDomElement>
|
||||
#include <QDebug>
|
||||
/**
|
||||
* Constructor
|
||||
@ -213,9 +215,6 @@ QString UAVObjectParser::parseXML(QString & xml, QString & filename)
|
||||
// Sort all fields according to size
|
||||
qStableSort(info->fields.begin(), info->fields.end(), fieldTypeLessThan);
|
||||
|
||||
// Sort all fields according to size
|
||||
qStableSort(info->fields.begin(), info->fields.end(), fieldTypeLessThan);
|
||||
|
||||
// Make sure that required elements were found
|
||||
if (!fieldFound) {
|
||||
return QString("Object::field element is missing");
|
||||
|
@ -30,8 +30,6 @@
|
||||
#include <QString>
|
||||
#include <QStringList>
|
||||
#include <QList>
|
||||
#include <QDomDocument>
|
||||
#include <QDomElement>
|
||||
#include <QDomNode>
|
||||
#include <QByteArray>
|
||||
|
||||
|
BIN
hardware/Derivative/Spedix_CC3D_V2/CC3D_V2.PcbDoc
Normal file
BIN
hardware/Derivative/Spedix_CC3D_V2/CC3D_V2.PcbDoc
Normal file
Binary file not shown.
BIN
hardware/Derivative/Spedix_CC3D_V2/CC3D_V2.SchDoc
Normal file
BIN
hardware/Derivative/Spedix_CC3D_V2/CC3D_V2.SchDoc
Normal file
Binary file not shown.
1104
hardware/Derivative/Spedix_CC3D_V2/CopterControl 3D_V2.PrjPcb
Normal file
1104
hardware/Derivative/Spedix_CC3D_V2/CopterControl 3D_V2.PrjPcb
Normal file
@ -0,0 +1,1104 @@
|
||||
[Design]
|
||||
Version=1.0
|
||||
HierarchyMode=0
|
||||
ChannelRoomNamingStyle=0
|
||||
OutputPath=Project Outputs for CopterControl 3D
|
||||
LogFolderPath=
|
||||
ChannelDesignatorFormatString=$Component_$RoomName
|
||||
ChannelRoomLevelSeperator=_
|
||||
OpenOutputs=1
|
||||
ArchiveProject=0
|
||||
TimestampOutput=0
|
||||
SeparateFolders=0
|
||||
PinSwapBy_Netlabel=1
|
||||
PinSwapBy_Pin=1
|
||||
AllowPortNetNames=0
|
||||
AllowSheetEntryNetNames=1
|
||||
AppendSheetNumberToLocalNets=0
|
||||
NetlistSinglePinNets=0
|
||||
DefaultConfiguration=
|
||||
UserID=0xFFFFFFFF
|
||||
DefaultPcbProtel=1
|
||||
DefaultPcbPcad=0
|
||||
ReorderDocumentsOnCompile=1
|
||||
NameNetsHierarchically=0
|
||||
PowerPortNamesTakePriority=0
|
||||
PushECOToAnnotationFile=1
|
||||
DItemRevisionGUID=
|
||||
|
||||
[Document1]
|
||||
DocumentPath=..\CopterControl 3D1\CopterControl 3D1.PcbLib
|
||||
AnnotationEnabled=1
|
||||
AnnotateStartValue=1
|
||||
AnnotationIndexControlEnabled=0
|
||||
AnnotateSuffix=
|
||||
AnnotateScope=All
|
||||
AnnotateOrder=-1
|
||||
DoLibraryUpdate=1
|
||||
DoDatabaseUpdate=1
|
||||
ClassGenCCAutoEnabled=1
|
||||
ClassGenCCAutoRoomEnabled=1
|
||||
ClassGenNCAutoScope=None
|
||||
DItemRevisionGUID=
|
||||
|
||||
[Document2]
|
||||
DocumentPath=CC3D_V2.PcbDoc
|
||||
AnnotationEnabled=1
|
||||
AnnotateStartValue=1
|
||||
AnnotationIndexControlEnabled=0
|
||||
AnnotateSuffix=
|
||||
AnnotateScope=All
|
||||
AnnotateOrder=-1
|
||||
DoLibraryUpdate=1
|
||||
DoDatabaseUpdate=1
|
||||
ClassGenCCAutoEnabled=1
|
||||
ClassGenCCAutoRoomEnabled=1
|
||||
ClassGenNCAutoScope=None
|
||||
DItemRevisionGUID=
|
||||
|
||||
[Document3]
|
||||
DocumentPath=CC3D_V2.SchDoc
|
||||
AnnotationEnabled=1
|
||||
AnnotateStartValue=1
|
||||
AnnotationIndexControlEnabled=0
|
||||
AnnotateSuffix=
|
||||
AnnotateScope=All
|
||||
AnnotateOrder=0
|
||||
DoLibraryUpdate=1
|
||||
DoDatabaseUpdate=1
|
||||
ClassGenCCAutoEnabled=1
|
||||
ClassGenCCAutoRoomEnabled=0
|
||||
ClassGenNCAutoScope=None
|
||||
DItemRevisionGUID=
|
||||
|
||||
[Document4]
|
||||
DocumentPath=..\Assembly.OutJob
|
||||
AnnotationEnabled=1
|
||||
AnnotateStartValue=1
|
||||
AnnotationIndexControlEnabled=0
|
||||
AnnotateSuffix=
|
||||
AnnotateScope=All
|
||||
AnnotateOrder=-1
|
||||
DoLibraryUpdate=1
|
||||
DoDatabaseUpdate=1
|
||||
ClassGenCCAutoEnabled=1
|
||||
ClassGenCCAutoRoomEnabled=1
|
||||
ClassGenNCAutoScope=None
|
||||
DItemRevisionGUID=
|
||||
|
||||
[Document5]
|
||||
DocumentPath=..\CopterControl 3D.IntLib
|
||||
AnnotationEnabled=1
|
||||
AnnotateStartValue=1
|
||||
AnnotationIndexControlEnabled=0
|
||||
AnnotateSuffix=
|
||||
AnnotateScope=All
|
||||
AnnotateOrder=-1
|
||||
DoLibraryUpdate=1
|
||||
DoDatabaseUpdate=1
|
||||
ClassGenCCAutoEnabled=1
|
||||
ClassGenCCAutoRoomEnabled=1
|
||||
ClassGenNCAutoScope=None
|
||||
DItemRevisionGUID=
|
||||
|
||||
[GeneratedDocument1]
|
||||
DocumentPath=..\Project Outputs for CopterControl 3D\Design Rule Check - CC3D_V1.html
|
||||
DItemRevisionGUID=
|
||||
|
||||
[SearchPath1]
|
||||
Path=..\..\..\..\Program Files (x86)\Altium Designer Summer 09\Library\*.*
|
||||
IncludeSubFolders=1
|
||||
|
||||
[Generic_SmartPDF]
|
||||
AutoOpenFile=0
|
||||
AutoOpenOutJob=-1
|
||||
|
||||
[Generic_SmartPDFSettings]
|
||||
ProjectMode=0
|
||||
ZoomPrecision=50
|
||||
AddNetsInformation=-1
|
||||
AddNetPins=-1
|
||||
AddNetNetLabels=-1
|
||||
AddNetPorts=-1
|
||||
ExportBOM=0
|
||||
TemplateFilename=
|
||||
TemplateStoreRelative=-1
|
||||
PCB_PrintColor=0
|
||||
SCH_PrintColor=0
|
||||
SCH_ShowNoErc=0
|
||||
SCH_ShowParameter=0
|
||||
SCH_ShowProbes=0
|
||||
SCH_ShowBlankets=0
|
||||
OutputFileName=CopterControl.SchDoc=C:\Users\David\Documents\SVN\WIP\trunk\hardware\production\CopterControl\CopterControl Schematic.pdf
|
||||
SCH_ExpandLogicalToPhysical=0
|
||||
SCH_VariantName=[No Variations]
|
||||
SCH_ExpandComponentDesignators=-1
|
||||
SCH_ExpandNetlabels=0
|
||||
SCH_ExpandPorts=0
|
||||
SCH_ExpandSheetNumber=0
|
||||
SCH_ExpandDocumentNumber=0
|
||||
SCH_HasExpandLogicalToPhysicalSheets=-1
|
||||
SaveSettingsToOutJob=0
|
||||
SCH_NoERCSymbolsToShow="Thin Cross","Thick Cross","Small Cross",Checkbox,Triangle
|
||||
SCH_ShowNote=-1
|
||||
SCH_ShowNoteCollapsed=-1
|
||||
|
||||
[OutputGroup1]
|
||||
Name=Netlist Outputs
|
||||
Description=
|
||||
TargetPrinter=FX Docuprint M158 f-00000
|
||||
PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1
|
||||
OutputType1=CadnetixNetlist
|
||||
OutputName1=Cadnetix Netlist
|
||||
OutputDocumentPath1=
|
||||
OutputVariantName1=
|
||||
OutputDefault1=0
|
||||
OutputType2=CalayNetlist
|
||||
OutputName2=Calay Netlist
|
||||
OutputDocumentPath2=
|
||||
OutputVariantName2=
|
||||
OutputDefault2=0
|
||||
OutputType3=EDIF
|
||||
OutputName3=EDIF for PCB
|
||||
OutputDocumentPath3=
|
||||
OutputVariantName3=
|
||||
OutputDefault3=0
|
||||
OutputType4=EESofNetlist
|
||||
OutputName4=EESof Netlist
|
||||
OutputDocumentPath4=
|
||||
OutputVariantName4=
|
||||
OutputDefault4=0
|
||||
OutputType5=IntergraphNetlist
|
||||
OutputName5=Intergraph Netlist
|
||||
OutputDocumentPath5=
|
||||
OutputVariantName5=
|
||||
OutputDefault5=0
|
||||
OutputType6=MentorBoardStationNetlist
|
||||
OutputName6=Mentor BoardStation Netlist
|
||||
OutputDocumentPath6=
|
||||
OutputVariantName6=
|
||||
OutputDefault6=0
|
||||
OutputType7=MultiWire
|
||||
OutputName7=MultiWire
|
||||
OutputDocumentPath7=
|
||||
OutputVariantName7=
|
||||
OutputDefault7=0
|
||||
OutputType8=OrCadPCB2Netlist
|
||||
OutputName8=Orcad/PCB2 Netlist
|
||||
OutputDocumentPath8=
|
||||
OutputVariantName8=
|
||||
OutputDefault8=0
|
||||
OutputType9=PADSNetlist
|
||||
OutputName9=PADS ASCII Netlist
|
||||
OutputDocumentPath9=
|
||||
OutputVariantName9=
|
||||
OutputDefault9=0
|
||||
OutputType10=Pcad
|
||||
OutputName10=Pcad for PCB
|
||||
OutputDocumentPath10=
|
||||
OutputVariantName10=
|
||||
OutputDefault10=0
|
||||
OutputType11=PCADNetlist
|
||||
OutputName11=PCAD Netlist
|
||||
OutputDocumentPath11=
|
||||
OutputVariantName11=
|
||||
OutputDefault11=0
|
||||
OutputType12=PCADnltNetlist
|
||||
OutputName12=PCADnlt Netlist
|
||||
OutputDocumentPath12=
|
||||
OutputVariantName12=
|
||||
OutputDefault12=0
|
||||
OutputType13=Protel2Netlist
|
||||
OutputName13=Protel2 Netlist
|
||||
OutputDocumentPath13=
|
||||
OutputVariantName13=
|
||||
OutputDefault13=0
|
||||
OutputType14=ProtelNetlist
|
||||
OutputName14=Protel
|
||||
OutputDocumentPath14=
|
||||
OutputVariantName14=
|
||||
OutputDefault14=0
|
||||
OutputType15=RacalNetlist
|
||||
OutputName15=Racal Netlist
|
||||
OutputDocumentPath15=
|
||||
OutputVariantName15=
|
||||
OutputDefault15=0
|
||||
OutputType16=RINFNetlist
|
||||
OutputName16=RINF Netlist
|
||||
OutputDocumentPath16=
|
||||
OutputVariantName16=
|
||||
OutputDefault16=0
|
||||
OutputType17=SciCardsNetlist
|
||||
OutputName17=SciCards Netlist
|
||||
OutputDocumentPath17=
|
||||
OutputVariantName17=
|
||||
OutputDefault17=0
|
||||
OutputType18=SIMetrixNetlist
|
||||
OutputName18=SIMetrix
|
||||
OutputDocumentPath18=
|
||||
OutputVariantName18=
|
||||
OutputDefault18=0
|
||||
OutputType19=SIMPLISNetlist
|
||||
OutputName19=SIMPLIS
|
||||
OutputDocumentPath19=
|
||||
OutputVariantName19=
|
||||
OutputDefault19=0
|
||||
OutputType20=TangoNetlist
|
||||
OutputName20=Tango Netlist
|
||||
OutputDocumentPath20=
|
||||
OutputVariantName20=
|
||||
OutputDefault20=0
|
||||
OutputType21=TelesisNetlist
|
||||
OutputName21=Telesis Netlist
|
||||
OutputDocumentPath21=
|
||||
OutputVariantName21=
|
||||
OutputDefault21=0
|
||||
OutputType22=Verilog
|
||||
OutputName22=Verilog File
|
||||
OutputDocumentPath22=
|
||||
OutputVariantName22=
|
||||
OutputDefault22=0
|
||||
OutputType23=VHDL
|
||||
OutputName23=VHDL File
|
||||
OutputDocumentPath23=
|
||||
OutputVariantName23=
|
||||
OutputDefault23=0
|
||||
OutputType24=WireListNetlist
|
||||
OutputName24=WireList Netlist
|
||||
OutputDocumentPath24=
|
||||
OutputVariantName24=
|
||||
OutputDefault24=0
|
||||
OutputType25=XSpiceNetlist
|
||||
OutputName25=XSpice Netlist
|
||||
OutputDocumentPath25=
|
||||
OutputVariantName25=
|
||||
OutputDefault25=0
|
||||
|
||||
[OutputGroup2]
|
||||
Name=Simulator Outputs
|
||||
Description=
|
||||
TargetPrinter=FX Docuprint M158 f-00000
|
||||
PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1
|
||||
OutputType1=AdvSimNetlist
|
||||
OutputName1=Mixed Sim
|
||||
OutputDocumentPath1=
|
||||
OutputVariantName1=
|
||||
OutputDefault1=0
|
||||
OutputType2=SIMetrix_Sim
|
||||
OutputName2=SIMetrix
|
||||
OutputDocumentPath2=
|
||||
OutputVariantName2=
|
||||
OutputDefault2=0
|
||||
OutputType3=SIMPLIS_Sim
|
||||
OutputName3=SIMPLIS
|
||||
OutputDocumentPath3=
|
||||
OutputVariantName3=
|
||||
OutputDefault3=0
|
||||
|
||||
[OutputGroup3]
|
||||
Name=Documentation Outputs
|
||||
Description=
|
||||
TargetPrinter=FX Docuprint M158 f-00000
|
||||
PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1
|
||||
OutputType1=Composite
|
||||
OutputName1=Composite Drawing
|
||||
OutputDocumentPath1=C:\Users\David\Documents\SVN\OP-WIP\trunk\hardware\production\CopterControl\CopterControl.PcbDoc
|
||||
OutputVariantName1=
|
||||
OutputDefault1=0
|
||||
PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=0
|
||||
Configuration1_Name1=OutputConfigurationParameter1
|
||||
Configuration1_Item1=PrintArea=DesignExtent|PrintAreaLowerLeftCornerX=0|PrintAreaLowerLeftCornerY=0|PrintAreaUpperRightCornerX=0|PrintAreaUpperRightCornerY=0|Record=PcbPrintView
|
||||
Configuration1_Name2=OutputConfigurationParameter2
|
||||
Configuration1_Item2=IncludeBottomLayerComponents=True|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=True|Index=0|Mirror=False|Name=Multilayer Composite Print|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False
|
||||
Configuration1_Name3=OutputConfigurationParameter3
|
||||
Configuration1_Item3=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopOverlay|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration1_Name4=OutputConfigurationParameter4
|
||||
Configuration1_Item4=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomOverlay|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration1_Name5=OutputConfigurationParameter5
|
||||
Configuration1_Item5=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration1_Name6=OutputConfigurationParameter6
|
||||
Configuration1_Item6=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=MidLayer1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration1_Name7=OutputConfigurationParameter7
|
||||
Configuration1_Item7=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration1_Name8=OutputConfigurationParameter8
|
||||
Configuration1_Item8=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration1_Name9=OutputConfigurationParameter9
|
||||
Configuration1_Item9=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical5|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration1_Name10=OutputConfigurationParameter10
|
||||
Configuration1_Item10=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical6|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration1_Name11=OutputConfigurationParameter11
|
||||
Configuration1_Item11=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical7|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration1_Name12=OutputConfigurationParameter12
|
||||
Configuration1_Item12=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration1_Name13=OutputConfigurationParameter13
|
||||
Configuration1_Item13=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration1_Name14=OutputConfigurationParameter14
|
||||
Configuration1_Item14=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=MultiLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
OutputType2=Logic Analyser Print
|
||||
OutputName2=Logic Analyser Prints
|
||||
OutputDocumentPath2=
|
||||
OutputVariantName2=
|
||||
OutputDefault2=0
|
||||
PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType3=OpenBus Print
|
||||
OutputName3=OpenBus Prints
|
||||
OutputDocumentPath3=
|
||||
OutputVariantName3=
|
||||
OutputDefault3=0
|
||||
PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType4=PCB 3D Print
|
||||
OutputName4=PCB 3D Prints
|
||||
OutputDocumentPath4=
|
||||
OutputVariantName4=[No Variations]
|
||||
OutputDefault4=0
|
||||
PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType5=PCB Print
|
||||
OutputName5=PCB Prints
|
||||
OutputDocumentPath5=
|
||||
OutputVariantName5=
|
||||
OutputDefault5=0
|
||||
PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType6=Schematic Print
|
||||
OutputName6=Schematic Prints
|
||||
OutputDocumentPath6=
|
||||
OutputVariantName6=
|
||||
OutputDefault6=0
|
||||
PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType7=SimView Print
|
||||
OutputName7=SimView Prints
|
||||
OutputDocumentPath7=
|
||||
OutputVariantName7=
|
||||
OutputDefault7=0
|
||||
PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType8=Wave Print
|
||||
OutputName8=Wave Prints
|
||||
OutputDocumentPath8=
|
||||
OutputVariantName8=
|
||||
OutputDefault8=0
|
||||
PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType9=WaveSim Print
|
||||
OutputName9=WaveSim Prints
|
||||
OutputDocumentPath9=
|
||||
OutputVariantName9=
|
||||
OutputDefault9=0
|
||||
PageOptions9=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
|
||||
[OutputGroup4]
|
||||
Name=Assembly Outputs
|
||||
Description=
|
||||
TargetPrinter=FX Docuprint M158 f-00000
|
||||
PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1
|
||||
OutputType1=Assembly
|
||||
OutputName1=Assembly Drawings
|
||||
OutputDocumentPath1=
|
||||
OutputVariantName1=[No Variations]
|
||||
OutputDefault1=0
|
||||
PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType2=Pick Place
|
||||
OutputName2=Generates pick and place files
|
||||
OutputDocumentPath2=
|
||||
OutputVariantName2=[No Variations]
|
||||
OutputDefault2=0
|
||||
OutputType3=Test Points For Assembly
|
||||
OutputName3=Test Point Report
|
||||
OutputDocumentPath3=
|
||||
OutputVariantName3=[No Variations]
|
||||
OutputDefault3=0
|
||||
|
||||
[OutputGroup5]
|
||||
Name=Fabrication Outputs
|
||||
Description=
|
||||
TargetPrinter=FX Docuprint M158 f-00000
|
||||
PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1
|
||||
OutputType1=ODB
|
||||
OutputName1=ODB++ Files
|
||||
OutputDocumentPath1=
|
||||
OutputVariantName1=[No Variations]
|
||||
OutputDefault1=0
|
||||
OutputType2=NC Drill
|
||||
OutputName2=NC Drill Files
|
||||
OutputDocumentPath2=
|
||||
OutputVariantName2=
|
||||
OutputDefault2=0
|
||||
Configuration2_Name1=OutputConfigurationParameter1
|
||||
Configuration2_Item1=BoardEdgeRoutToolDia=2000000|GenerateBoardEdgeRout=False|GenerateDrilledSlotsG85=False|GenerateEIADrillFile=False|GenerateSeparatePlatedNonPlatedFiles=False|NumberOfDecimals=5|NumberOfUnits=2|OptimizeChangeLocationCommands=True|OriginPosition=Relative|Record=DrillView|Units=Imperial|ZeroesMode=SuppressTrailingZeroes
|
||||
OutputType3=Test Points
|
||||
OutputName3=Test Point Report
|
||||
OutputDocumentPath3=
|
||||
OutputVariantName3=
|
||||
OutputDefault3=0
|
||||
OutputType4=Plane
|
||||
OutputName4=Power-Plane Prints
|
||||
OutputDocumentPath4=
|
||||
OutputVariantName4=
|
||||
OutputDefault4=0
|
||||
PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType5=Mask
|
||||
OutputName5=Solder/Paste Mask Prints
|
||||
OutputDocumentPath5=
|
||||
OutputVariantName5=
|
||||
OutputDefault5=0
|
||||
PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType6=Drill
|
||||
OutputName6=Drill Drawing/Guides
|
||||
OutputDocumentPath6=
|
||||
OutputVariantName6=
|
||||
OutputDefault6=0
|
||||
PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=4.20|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
Configuration6_Name1=OutputConfigurationParameter1
|
||||
Configuration6_Item1=PrintArea=DesignExtent|PrintAreaLowerLeftCornerX=0|PrintAreaLowerLeftCornerY=0|PrintAreaUpperRightCornerX=0|PrintAreaUpperRightCornerY=0|Record=PcbPrintView
|
||||
Configuration6_Name2=OutputConfigurationParameter2
|
||||
Configuration6_Item2=IncludeBottomLayerComponents=True|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=True|Index=0|Mirror=False|Name=Drill Drawing For (Bottom Layer,Top Layer)|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False
|
||||
Configuration6_Name3=OutputConfigurationParameter3
|
||||
Configuration6_Item3=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=BottomLayer|DLayer2=TopLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=DrillDrawing|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration6_Name4=OutputConfigurationParameter4
|
||||
Configuration6_Item4=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration6_Name5=OutputConfigurationParameter5
|
||||
Configuration6_Item5=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical5|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration6_Name6=OutputConfigurationParameter6
|
||||
Configuration6_Item6=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical6|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration6_Name7=OutputConfigurationParameter7
|
||||
Configuration6_Item7=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical7|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration6_Name8=OutputConfigurationParameter8
|
||||
Configuration6_Item8=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration6_Name9=OutputConfigurationParameter9
|
||||
Configuration6_Item9=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration6_Name10=OutputConfigurationParameter10
|
||||
Configuration6_Item10=IncludeBottomLayerComponents=True|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=True|Index=1|Mirror=False|Name=Drill Guide For (Bottom Layer,Top Layer)|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False
|
||||
Configuration6_Name11=OutputConfigurationParameter11
|
||||
Configuration6_Item11=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=BottomLayer|DLayer2=TopLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=DrillGuide|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer
|
||||
Configuration6_Name12=OutputConfigurationParameter12
|
||||
Configuration6_Item12=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer
|
||||
Configuration6_Name13=OutputConfigurationParameter13
|
||||
Configuration6_Item13=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical5|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer
|
||||
Configuration6_Name14=OutputConfigurationParameter14
|
||||
Configuration6_Item14=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical6|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer
|
||||
Configuration6_Name15=OutputConfigurationParameter15
|
||||
Configuration6_Item15=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical7|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer
|
||||
Configuration6_Name16=OutputConfigurationParameter16
|
||||
Configuration6_Item16=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer
|
||||
Configuration6_Name17=OutputConfigurationParameter17
|
||||
Configuration6_Item17=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer
|
||||
OutputType7=CompositeDrill
|
||||
OutputName7=Composite Drill Drawing
|
||||
OutputDocumentPath7=
|
||||
OutputVariantName7=
|
||||
OutputDefault7=0
|
||||
PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType8=Final
|
||||
OutputName8=Final Artwork Prints
|
||||
OutputDocumentPath8=
|
||||
OutputVariantName8=[No Variations]
|
||||
OutputDefault8=0
|
||||
PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType9=Gerber
|
||||
OutputName9=Gerber Files
|
||||
OutputDocumentPath9=
|
||||
OutputVariantName9=[No Variations]
|
||||
OutputDefault9=0
|
||||
Configuration9_Name1=OutputConfigurationParameter1
|
||||
Configuration9_Item1=AddToAllPlots.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean|CentrePlots=False|DrillDrawingSymbol=GraphicsSymbol|DrillDrawingSymbolSize=500000|EmbeddedApertures=True|FilmBorderSize=10000000|FilmXSize=200000000|FilmYSize=160000000|FlashAllFills=False|FlashPadShapes=True|G54OnApertureChange=False|GenerateDRCRulesFile=True|GenerateReliefShapes=True|GerberUnit=Imperial|IncludeUnconnectedMidLayerPads=False|LeadingAndTrailingZeroesMode=SuppressLeadingZeroes|MaxApertureSize=2500000|MinusApertureTolerance=50|Mirror.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean|MirrorDrillDrawingPlots=False|MirrorDrillGuidePlots=False|NumberOfDecimals=5|OptimizeChangeLocationCommands=True|OriginPosition=Relative|Panelize=False|Plot.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean,16973830~1,16973832~1,16973834~1,16777217~1,16842751~1,16973835~1,16973833~1,16973831~1,16908289~1,16908293~1,16973837~1,16973848~1,16973849~1|PlotPositivePlaneLayers=False|PlotUsedDrillDrawingLayerPairs=True|PlotUsedDrillGuideLayerPairs=True|PlusApertureTolerance=50|Record=GerberView|SoftwareArcs=False|Sorted=False
|
||||
|
||||
[OutputGroup6]
|
||||
Name=Report Outputs
|
||||
Description=
|
||||
TargetPrinter=FX Docuprint M158 f-00000
|
||||
PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1
|
||||
OutputType1=BOM_PartType
|
||||
OutputName1=Bill of Materials
|
||||
OutputDocumentPath1=
|
||||
OutputVariantName1=[No Variations]
|
||||
OutputDefault1=0
|
||||
PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
Configuration1_Name1=Filter
|
||||
Configuration1_Item1=545046300E5446696C74657257726170706572000D46696C7465722E416374697665090F46696C7465722E43726974657269610A04000000000000000000
|
||||
Configuration1_Name2=General
|
||||
Configuration1_Item2=OpenExported=True|AddToProject=False|ForceFit=False|NotFitted=False|Database=False|IncludePCBData=False|ShowExportOptions=True|TemplateFilename=..\Altium\BOM Digikey.xlt|BatchMode=5|FormWidth=1401|FormHeight=641|SupplierProdQty=1000|SupplierAutoQty=True|SupplierUseCachedPricing=True|SupplierCurrency=<none>
|
||||
Configuration1_Name3=GroupOrder
|
||||
Configuration1_Item3=Supplier Part Number 1=True
|
||||
Configuration1_Name4=OutputConfigurationParameter1
|
||||
Configuration1_Item4=Record=BOMPrintView|ShowNoERC=True|ShowParamSet=True|ShowProbe=True|ShowBlanket=True|ExpandDesignator=True|ExpandNetLabel=False|ExpandPort=False|ExpandSheetNum=False|ExpandDocNum=False
|
||||
Configuration1_Name5=PCBDocument
|
||||
Configuration1_Item5=
|
||||
Configuration1_Name6=SortOrder
|
||||
Configuration1_Item6=Description=Up
|
||||
Configuration1_Name7=VisibleOrder
|
||||
Configuration1_Item7=Description=113|Comment=77|Footprint=59|Value=40|Designator=56|Quantity=37|Supplier Part Number 1=174|Supplier Order Qty 1=30|Supplier Stock 1=38|Supplier Unit Price 1=29|Supplier Subtotal 1=30|Supplier 1=23|Manufacturer 1=32|Manufacturer Part Number 1=20
|
||||
OutputType2=ComponentCrossReference
|
||||
OutputName2=Component Cross Reference Report
|
||||
OutputDocumentPath2=
|
||||
OutputVariantName2=[No Variations]
|
||||
OutputDefault2=0
|
||||
OutputType3=ReportHierarchy
|
||||
OutputName3=Report Project Hierarchy
|
||||
OutputDocumentPath3=
|
||||
OutputVariantName3=[No Variations]
|
||||
OutputDefault3=0
|
||||
OutputType4=Script
|
||||
OutputName4=Script Output
|
||||
OutputDocumentPath4=
|
||||
OutputVariantName4=[No Variations]
|
||||
OutputDefault4=0
|
||||
OutputType5=SimpleBOM
|
||||
OutputName5=Simple BOM
|
||||
OutputDocumentPath5=
|
||||
OutputVariantName5=[No Variations]
|
||||
OutputDefault5=0
|
||||
OutputType6=SinglePinNetReporter
|
||||
OutputName6=Report Single Pin Nets
|
||||
OutputDocumentPath6=
|
||||
OutputVariantName6=[No Variations]
|
||||
OutputDefault6=0
|
||||
OutputType7=Design Rules Check
|
||||
OutputName7=Design Rules Check
|
||||
OutputDocumentPath7=
|
||||
OutputVariantName7=
|
||||
OutputDefault7=0
|
||||
PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType8=Electrical Rules Check
|
||||
OutputName8=Electrical Rules Check
|
||||
OutputDocumentPath8=
|
||||
OutputVariantName8=
|
||||
OutputDefault8=0
|
||||
PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
|
||||
[OutputGroup7]
|
||||
Name=Other Outputs
|
||||
Description=
|
||||
TargetPrinter=FX Docuprint M158 f-00000
|
||||
PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1
|
||||
OutputType1=Text Print
|
||||
OutputName1=Text Print
|
||||
OutputDocumentPath1=
|
||||
OutputVariantName1=
|
||||
OutputDefault1=0
|
||||
PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType2=Text Print
|
||||
OutputName2=Text Print
|
||||
OutputDocumentPath2=
|
||||
OutputVariantName2=
|
||||
OutputDefault2=0
|
||||
PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType3=Text Print
|
||||
OutputName3=Text Print
|
||||
OutputDocumentPath3=
|
||||
OutputVariantName3=
|
||||
OutputDefault3=0
|
||||
PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType4=Text Print
|
||||
OutputName4=Text Print
|
||||
OutputDocumentPath4=
|
||||
OutputVariantName4=
|
||||
OutputDefault4=0
|
||||
PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType5=Text Print
|
||||
OutputName5=Text Print
|
||||
OutputDocumentPath5=
|
||||
OutputVariantName5=
|
||||
OutputDefault5=0
|
||||
PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType6=Text Print
|
||||
OutputName6=Text Print
|
||||
OutputDocumentPath6=
|
||||
OutputVariantName6=
|
||||
OutputDefault6=0
|
||||
PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType7=Text Print
|
||||
OutputName7=Text Print
|
||||
OutputDocumentPath7=
|
||||
OutputVariantName7=
|
||||
OutputDefault7=0
|
||||
PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType8=Text Print
|
||||
OutputName8=Text Print
|
||||
OutputDocumentPath8=
|
||||
OutputVariantName8=
|
||||
OutputDefault8=0
|
||||
PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType9=Text Print
|
||||
OutputName9=Text Print
|
||||
OutputDocumentPath9=
|
||||
OutputVariantName9=
|
||||
OutputDefault9=0
|
||||
PageOptions9=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType10=Text Print
|
||||
OutputName10=Text Print
|
||||
OutputDocumentPath10=
|
||||
OutputVariantName10=
|
||||
OutputDefault10=0
|
||||
PageOptions10=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType11=Text Print
|
||||
OutputName11=Text Print
|
||||
OutputDocumentPath11=
|
||||
OutputVariantName11=
|
||||
OutputDefault11=0
|
||||
PageOptions11=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType12=Text Print
|
||||
OutputName12=Text Print
|
||||
OutputDocumentPath12=
|
||||
OutputVariantName12=
|
||||
OutputDefault12=0
|
||||
PageOptions12=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType13=Text Print
|
||||
OutputName13=Text Print
|
||||
OutputDocumentPath13=
|
||||
OutputVariantName13=
|
||||
OutputDefault13=0
|
||||
PageOptions13=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType14=Text Print
|
||||
OutputName14=Text Print
|
||||
OutputDocumentPath14=
|
||||
OutputVariantName14=
|
||||
OutputDefault14=0
|
||||
PageOptions14=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType15=Text Print
|
||||
OutputName15=Text Print
|
||||
OutputDocumentPath15=
|
||||
OutputVariantName15=
|
||||
OutputDefault15=0
|
||||
PageOptions15=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType16=Text Print
|
||||
OutputName16=Text Print
|
||||
OutputDocumentPath16=
|
||||
OutputVariantName16=
|
||||
OutputDefault16=0
|
||||
PageOptions16=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType17=Text Print
|
||||
OutputName17=Text Print
|
||||
OutputDocumentPath17=
|
||||
OutputVariantName17=
|
||||
OutputDefault17=0
|
||||
PageOptions17=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType18=Text Print
|
||||
OutputName18=Text Print
|
||||
OutputDocumentPath18=
|
||||
OutputVariantName18=
|
||||
OutputDefault18=0
|
||||
PageOptions18=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType19=Text Print
|
||||
OutputName19=Text Print
|
||||
OutputDocumentPath19=
|
||||
OutputVariantName19=
|
||||
OutputDefault19=0
|
||||
PageOptions19=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType20=Text Print
|
||||
OutputName20=Text Print
|
||||
OutputDocumentPath20=
|
||||
OutputVariantName20=
|
||||
OutputDefault20=0
|
||||
PageOptions20=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType21=Text Print
|
||||
OutputName21=Text Print
|
||||
OutputDocumentPath21=
|
||||
OutputVariantName21=
|
||||
OutputDefault21=0
|
||||
PageOptions21=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType22=Text Print
|
||||
OutputName22=Text Print
|
||||
OutputDocumentPath22=
|
||||
OutputVariantName22=
|
||||
OutputDefault22=0
|
||||
PageOptions22=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType23=Text Print
|
||||
OutputName23=Text Print
|
||||
OutputDocumentPath23=
|
||||
OutputVariantName23=
|
||||
OutputDefault23=0
|
||||
PageOptions23=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType24=Text Print
|
||||
OutputName24=Text Print
|
||||
OutputDocumentPath24=
|
||||
OutputVariantName24=
|
||||
OutputDefault24=0
|
||||
PageOptions24=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType25=Text Print
|
||||
OutputName25=Text Print
|
||||
OutputDocumentPath25=
|
||||
OutputVariantName25=
|
||||
OutputDefault25=0
|
||||
PageOptions25=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType26=Text Print
|
||||
OutputName26=Text Print
|
||||
OutputDocumentPath26=
|
||||
OutputVariantName26=
|
||||
OutputDefault26=0
|
||||
PageOptions26=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType27=Text Print
|
||||
OutputName27=Text Print
|
||||
OutputDocumentPath27=
|
||||
OutputVariantName27=
|
||||
OutputDefault27=0
|
||||
PageOptions27=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
OutputType28=Text Print
|
||||
OutputName28=Text Print
|
||||
OutputDocumentPath28=
|
||||
OutputVariantName28=
|
||||
OutputDefault28=0
|
||||
PageOptions28=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
|
||||
[Modification Levels]
|
||||
Type1=1
|
||||
Type2=1
|
||||
Type3=1
|
||||
Type4=1
|
||||
Type5=1
|
||||
Type6=1
|
||||
Type7=1
|
||||
Type8=1
|
||||
Type9=1
|
||||
Type10=1
|
||||
Type11=1
|
||||
Type12=1
|
||||
Type13=1
|
||||
Type14=1
|
||||
Type15=1
|
||||
Type16=1
|
||||
Type17=1
|
||||
Type18=1
|
||||
Type19=1
|
||||
Type20=1
|
||||
Type21=1
|
||||
Type22=1
|
||||
Type23=1
|
||||
Type24=1
|
||||
Type25=1
|
||||
Type26=1
|
||||
Type27=1
|
||||
Type28=1
|
||||
Type29=1
|
||||
Type30=1
|
||||
Type31=1
|
||||
Type32=1
|
||||
Type33=1
|
||||
Type34=1
|
||||
Type35=1
|
||||
Type36=1
|
||||
Type37=1
|
||||
Type38=1
|
||||
Type39=1
|
||||
Type40=1
|
||||
Type41=1
|
||||
Type42=1
|
||||
Type43=1
|
||||
Type44=1
|
||||
Type45=1
|
||||
Type46=1
|
||||
Type47=1
|
||||
Type48=1
|
||||
Type49=1
|
||||
Type50=1
|
||||
Type51=1
|
||||
Type52=1
|
||||
Type53=1
|
||||
Type54=1
|
||||
Type55=1
|
||||
Type56=1
|
||||
Type57=1
|
||||
Type58=1
|
||||
Type59=1
|
||||
Type60=1
|
||||
Type61=1
|
||||
Type62=1
|
||||
Type63=1
|
||||
Type64=1
|
||||
Type65=1
|
||||
Type66=1
|
||||
Type67=1
|
||||
Type68=1
|
||||
|
||||
[Difference Levels]
|
||||
Type1=1
|
||||
Type2=1
|
||||
Type3=1
|
||||
Type4=1
|
||||
Type5=1
|
||||
Type6=1
|
||||
Type7=1
|
||||
Type8=1
|
||||
Type9=1
|
||||
Type10=1
|
||||
Type11=1
|
||||
Type12=1
|
||||
Type13=1
|
||||
Type14=1
|
||||
Type15=1
|
||||
Type16=1
|
||||
Type17=1
|
||||
Type18=1
|
||||
Type19=1
|
||||
Type20=1
|
||||
Type21=1
|
||||
Type22=1
|
||||
Type23=1
|
||||
Type24=1
|
||||
Type25=1
|
||||
Type26=1
|
||||
Type27=1
|
||||
Type28=1
|
||||
Type29=1
|
||||
Type30=1
|
||||
Type31=1
|
||||
Type32=1
|
||||
Type33=1
|
||||
Type34=1
|
||||
Type35=1
|
||||
Type36=1
|
||||
|
||||
[Electrical Rules Check]
|
||||
Type1=1
|
||||
Type2=1
|
||||
Type3=2
|
||||
Type4=1
|
||||
Type5=2
|
||||
Type6=2
|
||||
Type7=1
|
||||
Type8=1
|
||||
Type9=1
|
||||
Type10=1
|
||||
Type11=2
|
||||
Type12=2
|
||||
Type13=2
|
||||
Type14=1
|
||||
Type15=1
|
||||
Type16=1
|
||||
Type17=1
|
||||
Type18=1
|
||||
Type19=1
|
||||
Type20=1
|
||||
Type21=1
|
||||
Type22=1
|
||||
Type23=1
|
||||
Type24=1
|
||||
Type25=2
|
||||
Type26=2
|
||||
Type27=2
|
||||
Type28=1
|
||||
Type29=1
|
||||
Type30=1
|
||||
Type31=1
|
||||
Type32=2
|
||||
Type33=2
|
||||
Type34=2
|
||||
Type35=1
|
||||
Type36=2
|
||||
Type37=1
|
||||
Type38=2
|
||||
Type39=2
|
||||
Type40=2
|
||||
Type41=0
|
||||
Type42=2
|
||||
Type43=1
|
||||
Type44=1
|
||||
Type45=2
|
||||
Type46=1
|
||||
Type47=2
|
||||
Type48=2
|
||||
Type49=1
|
||||
Type50=2
|
||||
Type51=1
|
||||
Type52=1
|
||||
Type53=1
|
||||
Type54=1
|
||||
Type55=1
|
||||
Type56=2
|
||||
Type57=1
|
||||
Type58=1
|
||||
Type59=0
|
||||
Type60=1
|
||||
Type61=2
|
||||
Type62=2
|
||||
Type63=1
|
||||
Type64=0
|
||||
Type65=2
|
||||
Type66=3
|
||||
Type67=2
|
||||
Type68=2
|
||||
Type69=1
|
||||
Type70=2
|
||||
Type71=2
|
||||
Type72=2
|
||||
Type73=2
|
||||
Type74=1
|
||||
Type75=2
|
||||
Type76=1
|
||||
Type77=1
|
||||
Type78=1
|
||||
Type79=1
|
||||
Type80=2
|
||||
Type81=3
|
||||
Type82=3
|
||||
Type83=3
|
||||
Type84=3
|
||||
Type85=3
|
||||
Type86=2
|
||||
Type87=2
|
||||
Type88=2
|
||||
Type89=1
|
||||
Type90=1
|
||||
Type91=3
|
||||
Type92=3
|
||||
Type93=2
|
||||
Type94=2
|
||||
Type95=2
|
||||
Type96=2
|
||||
Type97=2
|
||||
Type98=0
|
||||
|
||||
[ERC Connection Matrix]
|
||||
L1=NNNNNNNNNNNWNNNWW
|
||||
L2=NNWNNNNWWWNWNWNWN
|
||||
L3=NWEENEEEENEWNEEWN
|
||||
L4=NNENNNWEENNWNENWN
|
||||
L5=NNNNNNNNNNNNNNNNN
|
||||
L6=NNENNNNEENNWNENWN
|
||||
L7=NNEWNNWEENNWNENWN
|
||||
L8=NWEENEENEEENNEENN
|
||||
L9=NWEENEEEENEWNEEWW
|
||||
L10=NWNNNNNENNEWNNEWN
|
||||
L11=NNENNNNEEENWNENWN
|
||||
L12=WWWWNWWNWWWNWWWNN
|
||||
L13=NNNNNNNNNNNWNNNWW
|
||||
L14=NWEENEEEENEWNEEWW
|
||||
L15=NNENNNNEEENWNENWW
|
||||
L16=WWWWNWWNWWWNWWWNW
|
||||
L17=WNNNNNNNWNNNWWWWN
|
||||
|
||||
[Annotate]
|
||||
SortOrder=3
|
||||
MatchParameter1=Comment
|
||||
MatchStrictly1=1
|
||||
MatchParameter2=Library Reference
|
||||
MatchStrictly2=1
|
||||
PhysicalNamingFormat=$Component_$RoomName
|
||||
GlobalIndexSortOrder=3
|
||||
|
||||
[PrjClassGen]
|
||||
CompClassManualEnabled=0
|
||||
CompClassManualRoomEnabled=0
|
||||
NetClassAutoBusEnabled=1
|
||||
NetClassAutoCompEnabled=0
|
||||
NetClassAutoNamedHarnessEnabled=0
|
||||
NetClassManualEnabled=1
|
||||
|
||||
[LibraryUpdateOptions]
|
||||
SelectedOnly=0
|
||||
PartTypes=0
|
||||
ComponentLibIdentifierKind0=Library Name And Type
|
||||
ComponentLibraryIdentifier0=CopterControl.SchLib
|
||||
ComponentDesignItemID0=CC-STM32F103CBT6
|
||||
ComponentSymbolReference0=CC-STM32F103CBT6
|
||||
ComponentUpdate0=1
|
||||
ComponentIsDeviceSheet0=0
|
||||
FullReplace=1
|
||||
UpdateDesignatorLock=1
|
||||
UpdatePartIDLock=1
|
||||
DoGraphics=1
|
||||
DoParameters=1
|
||||
DoModels=1
|
||||
AddParameters=0
|
||||
RemoveParameters=0
|
||||
AddModels=1
|
||||
RemoveModels=1
|
||||
UpdateCurrentModels=1
|
||||
ParameterName0=Comment
|
||||
ParameterUpdate0=1
|
||||
ParameterName1=Component Kind
|
||||
ParameterUpdate1=1
|
||||
ParameterName2=ComponentLink1Description
|
||||
ParameterUpdate2=1
|
||||
ParameterName3=ComponentLink1URL
|
||||
ParameterUpdate3=1
|
||||
ParameterName4=ComponentLink2Description
|
||||
ParameterUpdate4=1
|
||||
ParameterName5=ComponentLink2URL
|
||||
ParameterUpdate5=1
|
||||
ParameterName6=DatasheetVersion
|
||||
ParameterUpdate6=1
|
||||
ParameterName7=Description
|
||||
ParameterUpdate7=1
|
||||
ParameterName8=Library Reference
|
||||
ParameterUpdate8=1
|
||||
ParameterName9=PackageDescription
|
||||
ParameterUpdate9=1
|
||||
ParameterName10=PackageReference
|
||||
ParameterUpdate10=1
|
||||
ParameterName11=PackageVersion
|
||||
ParameterUpdate11=1
|
||||
ParameterName12=Published
|
||||
ParameterUpdate12=1
|
||||
ParameterName13=Publisher
|
||||
ParameterUpdate13=1
|
||||
ParameterName14=Supplier 1
|
||||
ParameterUpdate14=1
|
||||
ParameterName15=Supplier Part Number 1
|
||||
ParameterUpdate15=1
|
||||
ModelTypeGroup0=PCBLIB
|
||||
ModelTypeUpdate0=1
|
||||
ModelType0=PCBLIB
|
||||
ModelName0=LQFP48_L
|
||||
ModelUpdate0=1
|
||||
ModelType1=PCBLIB
|
||||
ModelName1=LQFP48_M
|
||||
ModelUpdate1=1
|
||||
ModelType2=PCBLIB
|
||||
ModelName2=LQFP48_N
|
||||
ModelUpdate2=1
|
||||
|
||||
[DatabaseUpdateOptions]
|
||||
SelectedOnly=0
|
||||
PartTypes=0
|
||||
|
||||
[Comparison Options]
|
||||
ComparisonOptions0=Kind=Net|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0
|
||||
ComparisonOptions1=Kind=Net Class|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0
|
||||
ComparisonOptions2=Kind=Component Class|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0
|
||||
ComparisonOptions3=Kind=Rule|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0
|
||||
ComparisonOptions4=Kind=Differential Pair|MinPercent=50|MinMatch=1|ShowMatch=0|Confirm=0|UseName=0|InclAllRules=0
|
||||
|
||||
[SmartPDF]
|
||||
PageOptions=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1
|
||||
Configuration_Name1=OutputConfigurationParameter1
|
||||
Configuration_Item1=PrintArea=DesignExtent|PrintAreaLowerLeftCornerX=0|PrintAreaLowerLeftCornerY=0|PrintAreaUpperRightCornerX=0|PrintAreaUpperRightCornerY=0|Record=PcbPrintView
|
||||
Configuration_Name2=OutputConfigurationParameter2
|
||||
Configuration_Item2=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=0|Mirror=False|Name=Panel Details|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False
|
||||
Configuration_Name3=OutputConfigurationParameter3
|
||||
Configuration_Item3=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration_Name4=OutputConfigurationParameter4
|
||||
Configuration_Item4=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer
|
||||
Configuration_Name5=OutputConfigurationParameter5
|
||||
Configuration_Item5=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=1|Mirror=False|Name=Top SilkScreen|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False
|
||||
Configuration_Name6=OutputConfigurationParameter6
|
||||
Configuration_Item6=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopOverlay|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer
|
||||
Configuration_Name7=OutputConfigurationParameter7
|
||||
Configuration_Item7=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer
|
||||
Configuration_Name8=OutputConfigurationParameter8
|
||||
Configuration_Item8=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=2|Mirror=False|Name=Top Copper|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False
|
||||
Configuration_Name9=OutputConfigurationParameter9
|
||||
Configuration_Item9=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopLayer|Polygon=Full|PrintOutIndex=2|Record=PcbPrintLayer
|
||||
Configuration_Name10=OutputConfigurationParameter10
|
||||
Configuration_Item10=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=2|Record=PcbPrintLayer
|
||||
Configuration_Name11=OutputConfigurationParameter11
|
||||
Configuration_Item11=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=3|Mirror=False|Name=Groud Copper|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False
|
||||
Configuration_Name12=OutputConfigurationParameter12
|
||||
Configuration_Item12=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=MidLayer1|Polygon=Full|PrintOutIndex=3|Record=PcbPrintLayer
|
||||
Configuration_Name13=OutputConfigurationParameter13
|
||||
Configuration_Item13=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=3|Record=PcbPrintLayer
|
||||
Configuration_Name14=OutputConfigurationParameter14
|
||||
Configuration_Item14=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=4|Mirror=False|Name=Power Layer|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False
|
||||
Configuration_Name15=OutputConfigurationParameter15
|
||||
Configuration_Item15=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=MidLayer2|Polygon=Full|PrintOutIndex=4|Record=PcbPrintLayer
|
||||
Configuration_Name16=OutputConfigurationParameter16
|
||||
Configuration_Item16=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=4|Record=PcbPrintLayer
|
||||
Configuration_Name17=OutputConfigurationParameter17
|
||||
Configuration_Item17=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=5|Mirror=False|Name=Bottom Copper|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False
|
||||
Configuration_Name18=OutputConfigurationParameter18
|
||||
Configuration_Item18=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomLayer|Polygon=Full|PrintOutIndex=5|Record=PcbPrintLayer
|
||||
Configuration_Name19=OutputConfigurationParameter19
|
||||
Configuration_Item19=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=5|Record=PcbPrintLayer
|
||||
Configuration_Name20=OutputConfigurationParameter20
|
||||
Configuration_Item20=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=6|Mirror=False|Name=Bottom Silk Screen|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False
|
||||
Configuration_Name21=OutputConfigurationParameter21
|
||||
Configuration_Item21=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomOverlay|Polygon=Full|PrintOutIndex=6|Record=PcbPrintLayer
|
||||
Configuration_Name22=OutputConfigurationParameter22
|
||||
Configuration_Item22=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=6|Record=PcbPrintLayer
|
||||
|
BIN
hardware/Derivative/Spedix_CC3D_V2/IncorrectBootLoader-128.jpg
Normal file
BIN
hardware/Derivative/Spedix_CC3D_V2/IncorrectBootLoader-128.jpg
Normal file
Binary file not shown.
After Width: | Height: | Size: 63 KiB |
55
hardware/Derivative/Spedix_CC3D_V2/README.txt
Normal file
55
hardware/Derivative/Spedix_CC3D_V2/README.txt
Normal file
@ -0,0 +1,55 @@
|
||||
** Introduction **
|
||||
|
||||
These are all the hardware files for the OpenPilot CopterControl 3D, as re-manufactured by Spedix. The files
|
||||
represent complete schematic designs, and includes all Altium version 9 files. The work is based on the orignal
|
||||
CC3D design files located at: https://reviews.openpilot.org/browse/OpenPilot/hardware/Production/CopterControl%203D
|
||||
|
||||
** License **
|
||||
|
||||
These files are licensed under Creative Commons BY-SA 3.0 license. This license also that credit is given, in
|
||||
this case the OpenPilot logo should be retained at the same size as on the included files on any board produced
|
||||
or hardware derived from this design (which is a derivative of the original work).
|
||||
|
||||
For more details, please see: http://creativecommons.org/licenses/by-sa/3.0/au/deed.en
|
||||
|
||||
OpenPilot is a non-commercial project and releasing the original files to share with the wider community,
|
||||
please respect this and play fair. If there are any questions or items that need clarifying please contact
|
||||
one of the OpenPilot forum administrators.
|
||||
|
||||
Spedix has mofified the original design to include new connectors on the board for both Spectrum and S.Bus RX
|
||||
packages. This board can easily be identified by the added connectors as well as the Gold ENIG Openpilot logo.
|
||||
|
||||
This board was orignally shipped alongside the Spedix S250 ARF & BNF kits as sold by BuddyRC.
|
||||
|
||||
http://www.rcgroups.com/forums/showthread.php?t=2341341
|
||||
http://www.spedix-rc.com/index.php/multirotor/250-series.html
|
||||
http://www.buddyrc.com/spedix-s250-arf-kit-cc3d-version.html
|
||||
http://www.buddyrc.com/spedix-s250-bnf-cc3d-version.html
|
||||
|
||||
Additionally the board was sold standalone via BuddyRC. Other vendors may be reselling this board, however there
|
||||
is not a known list of potential resellers at this time.
|
||||
|
||||
http://www.buddyrc.com/cc3d-flight-control-board.html
|
||||
|
||||
Please note that the Gyro has been rotated on the board to make access to the USB port easier for end users with
|
||||
Mini frames. Pay attention to the arrow when mounting the board. This change eliminates the need for virtual
|
||||
rotation of the board within the software.
|
||||
|
||||
Also note that the first batches of this board shipped with an invalid bootloader. The verison number shows up
|
||||
as "-128". This bootloader seems to have timing issues which prevent it from being used with newer variants of
|
||||
the OpenPilot GCS. You will have to manually update the bootloader per the following instructions:
|
||||
|
||||
https://wiki.openpilot.org/display/WIKI/Bootloader+Update
|
||||
|
||||
** Caveats **
|
||||
|
||||
It has been pointed out by Failsafe(Jim) that the board appears to lack ESD protections.
|
||||
|
||||
** Credits **
|
||||
|
||||
David Ankers: concept, design and board creation.
|
||||
James Cotton: Firmware development, 3C algorythm, testing and advice.
|
||||
Cathy Moss: Design review, for being generally awesome and having patience for David's questions.
|
||||
Kevin Finisterre: Facilitating the exchange of CCBYSA materials from Spedix via BuddyRC, & creating the README.
|
||||
Dale Deng: Owner of BuddyRC, personally donating for all imported Spedix boards. Helping to obtain Spedix donations.
|
||||
Spedix: Modification of original design to incorperate S.Bus & Spectrum adaptor as well as rotation of Gyro.
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user