1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-12-01 09:24:10 +01:00

Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into abeck/OP-1769-Ground

This commit is contained in:
abeck70 2015-03-10 22:57:50 +11:00
commit f9b54fd6c8
42 changed files with 21365 additions and 11658 deletions

View File

@ -81,8 +81,10 @@ $(foreach var, $(SANITIZE_DEPRECATED_VARS), $(eval $(call SANITIZE_VAR,$(var),de
# Make sure this isn't being run as root unless installing (no whoami on Windows, but that is ok here)
ifeq ($(shell whoami 2>/dev/null),root)
ifeq ($(filter install all_clean,$(MAKECMDGOALS)),)
$(error You should not be running this as root)
ifeq ($(filter install,$(MAKECMDGOALS)),)
ifndef FAKEROOTKEY
$(error You should not be running this as root)
endif
endif
endif
@ -785,15 +787,19 @@ endif
# - calls paltform-specific packaging script
# Define some variables
export PACKAGE_LBL := $(shell $(VERSION_INFO) --format=\$${LABEL})
export PACKAGE_NAME := OpenPilot
export PACKAGE_SEP := -
PACKAGE_LBL := $(shell $(VERSION_INFO) --format=\$${LABEL})
PACKAGE_NAME := OpenPilot
PACKAGE_SEP := -
PACKAGE_FULL_NAME := $(PACKAGE_NAME)$(PACKAGE_SEP)$(PACKAGE_LBL)
# Source distribution is never dirty because it uses git archive
DIST_NAME := $(DIST_DIR)/$(subst dirty-,,$(PACKAGE_FULL_NAME)).tar
.PHONY: package
include $(ROOT_DIR)/package/$(UNAME).mk
package: all_fw all_ground uavobjects_matlab $(PACKAGE_DIR)
package: all_fw all_ground uavobjects_matlab | $(PACKAGE_DIR)
ifneq ($(GCS_BUILD_CONF),release)
# We can only package release builds
$(error Packaging is currently supported for release builds only)
@ -882,20 +888,20 @@ build-info:
DIST_VER_INFO := $(DIST_DIR)/version-info.json
.PHONY: $(DIST_VER_INFO) # Because to many deps to list
$(DIST_VER_INFO): $(DIST_DIR)
$(DIST_VER_INFO): .git/index | $(DIST_DIR)
$(V1) $(VERSION_INFO) --jsonpath="$(DIST_DIR)"
.PHONY: dist
dist: $(DIST_DIR) $(DIST_VER_INFO)
@$(ECHO) " SOURCE FOR DISTRIBUTION $(call toprel, $(DIST_DIR))"
$(eval DIST_NAME := $(call toprel, "$(DIST_DIR)/OpenPilot-$(shell git describe).tar"))
$(V1) git archive --prefix="OpenPilot/" -o "$(DIST_NAME)" HEAD
$(DIST_NAME).gz: $(DIST_VER_INFO) .git/index | $(DIST_DIR)
@$(ECHO) " SOURCE FOR DISTRIBUTION $(call toprel, $(DIST_NAME).gz)"
$(V1) git archive --prefix="$(PACKAGE_NAME)/" -o "$(DIST_NAME)" HEAD
$(V1) tar --append --file="$(DIST_NAME)" \
--transform='s,.*version-info.json,OpenPilot/version-info.json,' \
--transform='s,.*version-info.json,$(PACKAGE_NAME)/version-info.json,' \
$(call toprel, "$(DIST_VER_INFO)")
$(V1) gzip -f "$(DIST_NAME)"
.PHONY: dist
dist: $(DIST_NAME).gz
##############################
#

View File

@ -1,4 +1,4 @@
--- RELEASE-15.02 RC4
--- RELEASE-15.02 RC6
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.
A key improvement that helped achieve this was the addition of the PWMSync code path, this is now enabled by default. Some restrictions applies to CC3D/CC as it needs a compatible input method to enable PWMSync. Compatible input methods are PPM, S.Bus, DSM and OPLink. This release also introduces support for OneShot125 capable ESCs, such as the KISS ESCs and all ESCs supported in BLHeli V13 and above. Note that OneShot125 support has the same restrictions as PWMSync for CC and CC3D.
@ -10,12 +10,12 @@ Other enhancements include key parts of the GCS translated to Chinese and furthe
The full list of features, improvements and bugfixes in this release is accessible here:
https://progress.openpilot.org/issues/?filter=12161
Release Notes - OpenPilot - Version RELEASE-15.02
** Bug
* [OP-969] - Input Configuration Wizard has scrollbars showing up and next/previous buttons are pushed down out of sight
* [OP-1034] - CCPM Config Widget crashes GCS if required boxes aren't set i.e. Channel set to None
* [OP-1236] - Icons on Welcome tab - moves to the left
* [OP-1466] - Gcs crashes on Helicopter config tab
* [OP-1522] - Improve Robustness of OPLink radio
* [OP-1601] - Still not enough ram on CC for gps to be usable
@ -38,6 +38,8 @@ Release Notes - OpenPilot - Version RELEASE-15.02
* [OP-1755] - Add additional path for cloudconfigs
* [OP-1758] - Upgrade hidapi for all OSs (except windows) to solve mac issue:Fix incorrect device list after device removal
* [OP-1761] - Wizard bad config when PPM in, RapidESC out and hexa frame with CC/CC3D/Atom
* [OP-1764] - System should sanity check RC Input Channel value ranges and raise alarm accordingly
* [OP-1768] - PWM Sync and OneShot125 wizard output level and warning are incorrect
** Improvement
@ -60,13 +62,13 @@ Release Notes - OpenPilot - Version RELEASE-15.02
** Task
* [OP-1721] - C++ enable flight controller and upgrade ARM tools
* [OP-1738] - change default flight modes and thrust settings
* [OP-1747] - 15.02 rc1 motor end points do not reflect oneshot125 / pwmsync
** Sub task
* [OP-1748] - Chinese translation for 15.02
* [OP-1752] - Add Alarm sub status to SystemHealth
--- RELEASE-15.01 --- Look Ma, No hands ---
This release mainly focuses on a new feature, GPSAssist which is a new form of assisted control for multirotors.
Assisted Control provides assistance functions on top of existing flight modes. GPSAssist is the

View File

@ -43,7 +43,8 @@
#include <taskinfo.h>
// a number of useful macros
#define ADDSEVERITY(check) severity = (severity != SYSTEMALARMS_ALARM_OK ? severity : ((check) ? SYSTEMALARMS_ALARM_OK : SYSTEMALARMS_ALARM_CRITICAL))
#define ADDSEVERITY(check) severity = (severity != SYSTEMALARMS_ALARM_OK ? severity : ((check) ? SYSTEMALARMS_ALARM_OK : SYSTEMALARMS_ALARM_CRITICAL))
#define ADDEXTENDEDALARMSTATUS(error_code, error_substatus) if ((severity != SYSTEMALARMS_ALARM_OK) && (alarmstatus == SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE)) { alarmstatus = (error_code); alarmsubstatus = (error_substatus); }
// private types
typedef struct SANITYCHECK_CustomHookInstance {
@ -178,6 +179,27 @@ int32_t configuration_check()
}
}
// Check throttle/collective channel range for valid configuration of input for critical control
SystemSettingsThrustControlOptions thrustType;
SystemSettingsThrustControlGet(&thrustType);
ManualControlSettingsChannelMinData channelMin;
ManualControlSettingsChannelMaxData channelMax;
ManualControlSettingsChannelMinGet(&channelMin);
ManualControlSettingsChannelMaxGet(&channelMax);
switch (thrustType) {
case SYSTEMSETTINGS_THRUSTCONTROL_THROTTLE:
ADDSEVERITY(fabsf(channelMax.Throttle - channelMin.Throttle) > 300.0f);
ADDEXTENDEDALARMSTATUS(SYSTEMALARMS_EXTENDEDALARMSTATUS_BADTHROTTLEORCOLLECTIVEINPUTRANGE, 0);
break;
case SYSTEMSETTINGS_THRUSTCONTROL_COLLECTIVE:
ADDSEVERITY(fabsf(channelMax.Collective - channelMin.Collective) > 300.0f);
ADDEXTENDEDALARMSTATUS(SYSTEMALARMS_EXTENDEDALARMSTATUS_BADTHROTTLEORCOLLECTIVEINPUTRANGE, 0);
break;
default:
break;
}
// query sanity check hooks
if (severity < SYSTEMALARMS_ALARM_CRITICAL) {
SANITYCHECK_CustomHookInstance *instance = NULL;

View File

@ -0,0 +1,2185 @@
{
"battery": "2200 4s 60c",
"comment": "Bank 1 Acro + \nBank 2 Attitude mode\npids set for Blheli 13.xx and oneshot enabled",
"controller": "CC3D",
"esc": "Afro 30 Blheli 13.01",
"motor": "Blackout 2208 2000kv",
"name": "BlackOut B330 ",
"nick": "Failsafe",
"objects": [
{
"fields": [
{
"name": "VbarSensitivity",
"type": "float32",
"unit": "frac",
"values": [
{
"name": "Roll",
"value": 0.5
},
{
"name": "Pitch",
"value": 0.5
},
{
"name": "Yaw",
"value": 0.5
}
]
},
{
"name": "VbarRollPI",
"type": "float32",
"unit": "1/(deg/s)",
"values": [
{
"name": "Kp",
"value": 0.004999999888241291
},
{
"name": "Ki",
"value": 0.0020000000949949026
}
]
},
{
"name": "VbarPitchPI",
"type": "float32",
"unit": "1/(deg/s)",
"values": [
{
"name": "Kp",
"value": 0.004999999888241291
},
{
"name": "Ki",
"value": 0.0020000000949949026
}
]
},
{
"name": "VbarYawPI",
"type": "float32",
"unit": "1/(deg/s)",
"values": [
{
"name": "Kp",
"value": 0.004999999888241291
},
{
"name": "Ki",
"value": 0.0020000000949949026
}
]
},
{
"name": "VbarTau",
"type": "float32",
"unit": "sec",
"values": [
{
"name": "0",
"value": 0.5
}
]
},
{
"name": "GyroTau",
"type": "float32",
"unit": "",
"values": [
{
"name": "0",
"value": 0.004999999888241291
}
]
},
{
"name": "DerivativeGamma",
"type": "float32",
"unit": "",
"values": [
{
"name": "0",
"value": 1
}
]
},
{
"name": "AxisLockKp",
"type": "float32",
"unit": "",
"values": [
{
"name": "0",
"value": 2.5
}
]
},
{
"name": "WeakLevelingKp",
"type": "float32",
"unit": "(deg/s)/deg",
"values": [
{
"name": "0",
"value": 0.10000000149011612
}
]
},
{
"name": "CruiseControlMaxPowerFactor",
"type": "float32",
"unit": "x",
"values": [
{
"name": "0",
"value": 3
}
]
},
{
"name": "CruiseControlPowerTrim",
"type": "float32",
"unit": "%",
"values": [
{
"name": "0",
"value": 100
}
]
},
{
"name": "CruiseControlPowerDelayComp",
"type": "float32",
"unit": "sec",
"values": [
{
"name": "0",
"value": 0.25
}
]
},
{
"name": "ScaleToAirspeed",
"type": "float32",
"unit": "m/s",
"values": [
{
"name": "0",
"value": 0
}
]
},
{
"name": "ScaleToAirspeedLimits",
"type": "float32",
"unit": "",
"values": [
{
"name": "Min",
"value": 0.05000000074505806
},
{
"name": "Max",
"value": 3
}
]
},
{
"name": "FlightModeMap",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Bank1"
},
{
"name": "1",
"value": "Bank2"
},
{
"name": "2",
"value": "Bank1"
},
{
"name": "3",
"value": "Bank1"
},
{
"name": "4",
"value": "Bank1"
},
{
"name": "5",
"value": "Bank1"
}
]
},
{
"name": "VbarGyroSuppress",
"type": "int8",
"unit": "%",
"values": [
{
"name": "0",
"value": 30
}
]
},
{
"name": "VbarPiroComp",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "FALSE"
}
]
},
{
"name": "VbarMaxAngle",
"type": "uint8",
"unit": "deg",
"values": [
{
"name": "0",
"value": 10
}
]
},
{
"name": "DerivativeCutoff",
"type": "uint8",
"unit": "Hz",
"values": [
{
"name": "0",
"value": 20
}
]
},
{
"name": "MaxAxisLock",
"type": "uint8",
"unit": "deg",
"values": [
{
"name": "0",
"value": 30
}
]
},
{
"name": "MaxAxisLockRate",
"type": "uint8",
"unit": "deg/s",
"values": [
{
"name": "0",
"value": 2
}
]
},
{
"name": "MaxWeakLevelingRate",
"type": "uint8",
"unit": "deg/s",
"values": [
{
"name": "0",
"value": 5
}
]
},
{
"name": "RattitudeModeTransition",
"type": "uint8",
"unit": "%",
"values": [
{
"name": "0",
"value": 80
}
]
},
{
"name": "CruiseControlMinThrust",
"type": "int8",
"unit": "%",
"values": [
{
"name": "0",
"value": 5
}
]
},
{
"name": "CruiseControlMaxThrust",
"type": "uint8",
"unit": "%",
"values": [
{
"name": "0",
"value": 90
}
]
},
{
"name": "CruiseControlMaxAngle",
"type": "uint8",
"unit": "deg",
"values": [
{
"name": "0",
"value": 105
}
]
},
{
"name": "CruiseControlFlightModeSwitchPosEnable",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "FALSE"
},
{
"name": "1",
"value": "FALSE"
},
{
"name": "2",
"value": "FALSE"
},
{
"name": "3",
"value": "FALSE"
},
{
"name": "4",
"value": "FALSE"
},
{
"name": "5",
"value": "FALSE"
}
]
},
{
"name": "CruiseControlInvertedThrustReversing",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Unreversed"
}
]
},
{
"name": "CruiseControlInvertedPowerOutput",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Zero"
}
]
},
{
"name": "LowThrottleZeroIntegral",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "TRUE"
}
]
},
{
"name": "FlightModeAssistMap",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "None"
},
{
"name": "1",
"value": "None"
},
{
"name": "2",
"value": "None"
},
{
"name": "3",
"value": "None"
},
{
"name": "4",
"value": "None"
},
{
"name": "5",
"value": "None"
}
]
}
],
"id": "73603180",
"instance": 0,
"name": "StabilizationSettings",
"setting": true
},
{
"fields": [
{
"name": "ManualRate",
"type": "float32",
"unit": "degrees/sec",
"values": [
{
"name": "Roll",
"value": 200
},
{
"name": "Pitch",
"value": 200
},
{
"name": "Yaw",
"value": 220
}
]
},
{
"name": "MaximumRate",
"type": "float32",
"unit": "degrees/sec",
"values": [
{
"name": "Roll",
"value": 500
},
{
"name": "Pitch",
"value": 500
},
{
"name": "Yaw",
"value": 300
}
]
},
{
"name": "RollRatePID",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 0.002899999963119626
},
{
"name": "Ki",
"value": 0.0065000001341104507
},
{
"name": "Kd",
"value": 3.4000000596279278e-05
},
{
"name": "ILimit",
"value": 0.30000001192092896
}
]
},
{
"name": "PitchRatePID",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 0.004120000172406435
},
{
"name": "Ki",
"value": 0.0082999998703598976
},
{
"name": "Kd",
"value": 4.1999999666586518e-05
},
{
"name": "ILimit",
"value": 0.30000001192092896
}
]
},
{
"name": "YawRatePID",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 0.0086000002920627594
},
{
"name": "Ki",
"value": 0.014299999922513962
},
{
"name": "Kd",
"value": 4.9999998736893758e-05
},
{
"name": "ILimit",
"value": 0.30000001192092896
}
]
},
{
"name": "RollPI",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 2.9000000953674316
},
{
"name": "Ki",
"value": 0
},
{
"name": "ILimit",
"value": 50
}
]
},
{
"name": "PitchPI",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 3.2999999523162842
},
{
"name": "Ki",
"value": 0
},
{
"name": "ILimit",
"value": 50
}
]
},
{
"name": "YawPI",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 2.5
},
{
"name": "Ki",
"value": 0
},
{
"name": "ILimit",
"value": 50
}
]
},
{
"name": "AcroInsanityFactor",
"type": "float32",
"unit": "percent",
"values": [
{
"name": "0",
"value": 0.4699999988079071
}
]
},
{
"name": "ThrustPIDScaleCurve",
"type": "float32",
"unit": "percent",
"values": [
{
"name": "0",
"value": 0.0042716437019407749
},
{
"name": "25",
"value": -0.021436728537082672
},
{
"name": "50",
"value": -0.051431018859148026
},
{
"name": "75",
"value": -0.15000000596046448
},
{
"name": "100",
"value": -0.34714511036872864
}
]
},
{
"name": "RollMax",
"type": "uint8",
"unit": "degrees",
"values": [
{
"name": "0",
"value": 55
}
]
},
{
"name": "PitchMax",
"type": "uint8",
"unit": "degrees",
"values": [
{
"name": "0",
"value": 55
}
]
},
{
"name": "YawMax",
"type": "uint8",
"unit": "degrees",
"values": [
{
"name": "0",
"value": 35
}
]
},
{
"name": "StickExpo",
"type": "int8",
"unit": "percent",
"values": [
{
"name": "Roll",
"value": 12
},
{
"name": "Pitch",
"value": 12
},
{
"name": "Yaw",
"value": -5
}
]
},
{
"name": "EnablePiroComp",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "FALSE"
}
]
},
{
"name": "EnableThrustPIDScaling",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "TRUE"
}
]
},
{
"name": "ThrustPIDScaleSource",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "ActuatorDesiredThrust"
}
]
},
{
"name": "ThrustPIDScaleTarget",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "PD"
}
]
},
{
"name": "ThrustPIDScaleAxes",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Roll Pitch"
}
]
}
],
"id": "E8EBBD48",
"instance": 0,
"name": "StabilizationSettingsBank1",
"setting": true
},
{
"fields": [
{
"name": "ManualRate",
"type": "float32",
"unit": "degrees/sec",
"values": [
{
"name": "Roll",
"value": 200
},
{
"name": "Pitch",
"value": 200
},
{
"name": "Yaw",
"value": 220
}
]
},
{
"name": "MaximumRate",
"type": "float32",
"unit": "degrees/sec",
"values": [
{
"name": "Roll",
"value": 500
},
{
"name": "Pitch",
"value": 500
},
{
"name": "Yaw",
"value": 300
}
]
},
{
"name": "RollRatePID",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 0.00279999990016222
},
{
"name": "Ki",
"value": 0.0054999999701976776
},
{
"name": "Kd",
"value": 2.9000000722589903e-05
},
{
"name": "ILimit",
"value": 0.30000001192092896
}
]
},
{
"name": "PitchRatePID",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 0.0036200000904500484
},
{
"name": "Ki",
"value": 0.0086000002920627594
},
{
"name": "Kd",
"value": 3.600000127335079e-05
},
{
"name": "ILimit",
"value": 0.30000001192092896
}
]
},
{
"name": "YawRatePID",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 0.0086000002920627594
},
{
"name": "Ki",
"value": 0.014299999922513962
},
{
"name": "Kd",
"value": 4.9999998736893758e-05
},
{
"name": "ILimit",
"value": 0.30000001192092896
}
]
},
{
"name": "RollPI",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 3
},
{
"name": "Ki",
"value": 0
},
{
"name": "ILimit",
"value": 50
}
]
},
{
"name": "PitchPI",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 3.4000000953674316
},
{
"name": "Ki",
"value": 0
},
{
"name": "ILimit",
"value": 50
}
]
},
{
"name": "YawPI",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 2.5
},
{
"name": "Ki",
"value": 0
},
{
"name": "ILimit",
"value": 50
}
]
},
{
"name": "AcroInsanityFactor",
"type": "float32",
"unit": "percent",
"values": [
{
"name": "0",
"value": 0.40000000596046448
}
]
},
{
"name": "ThrustPIDScaleCurve",
"type": "float32",
"unit": "percent",
"values": [
{
"name": "0",
"value": 0.012843480333685875
},
{
"name": "25",
"value": -7.1359904723067302e-06
},
{
"name": "50",
"value": -0.12000571191310883
},
{
"name": "75",
"value": -0.18857327103614807
},
{
"name": "100",
"value": -0.25714081525802612
}
]
},
{
"name": "RollMax",
"type": "uint8",
"unit": "degrees",
"values": [
{
"name": "0",
"value": 55
}
]
},
{
"name": "PitchMax",
"type": "uint8",
"unit": "degrees",
"values": [
{
"name": "0",
"value": 55
}
]
},
{
"name": "YawMax",
"type": "uint8",
"unit": "degrees",
"values": [
{
"name": "0",
"value": 35
}
]
},
{
"name": "StickExpo",
"type": "int8",
"unit": "percent",
"values": [
{
"name": "Roll",
"value": 15
},
{
"name": "Pitch",
"value": 15
},
{
"name": "Yaw",
"value": -5
}
]
},
{
"name": "EnablePiroComp",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "FALSE"
}
]
},
{
"name": "EnableThrustPIDScaling",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "TRUE"
}
]
},
{
"name": "ThrustPIDScaleSource",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "ActuatorDesiredThrust"
}
]
},
{
"name": "ThrustPIDScaleTarget",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "PD"
}
]
},
{
"name": "ThrustPIDScaleAxes",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Roll Pitch"
}
]
}
],
"id": "70E9539A",
"instance": 0,
"name": "StabilizationSettingsBank2",
"setting": true
},
{
"fields": [
{
"name": "ManualRate",
"type": "float32",
"unit": "degrees/sec",
"values": [
{
"name": "Roll",
"value": 220
},
{
"name": "Pitch",
"value": 220
},
{
"name": "Yaw",
"value": 220
}
]
},
{
"name": "MaximumRate",
"type": "float32",
"unit": "degrees/sec",
"values": [
{
"name": "Roll",
"value": 300
},
{
"name": "Pitch",
"value": 300
},
{
"name": "Yaw",
"value": 300
}
]
},
{
"name": "RollRatePID",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 0.0024999999441206455
},
{
"name": "Ki",
"value": 0.0040000001899898052
},
{
"name": "Kd",
"value": 1.9999999494757503e-05
},
{
"name": "ILimit",
"value": 0.30000001192092896
}
]
},
{
"name": "PitchRatePID",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 0.0024999999441206455
},
{
"name": "Ki",
"value": 0.0040000001899898052
},
{
"name": "Kd",
"value": 1.9999999494757503e-05
},
{
"name": "ILimit",
"value": 0.30000001192092896
}
]
},
{
"name": "YawRatePID",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 0.0062000001780688763
},
{
"name": "Ki",
"value": 0.0099999997764825821
},
{
"name": "Kd",
"value": 4.9999998736893758e-05
},
{
"name": "ILimit",
"value": 0.30000001192092896
}
]
},
{
"name": "RollPI",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 2.5
},
{
"name": "Ki",
"value": 0
},
{
"name": "ILimit",
"value": 50
}
]
},
{
"name": "PitchPI",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 2.5
},
{
"name": "Ki",
"value": 0
},
{
"name": "ILimit",
"value": 50
}
]
},
{
"name": "YawPI",
"type": "float32",
"unit": "",
"values": [
{
"name": "Kp",
"value": 2.5
},
{
"name": "Ki",
"value": 0
},
{
"name": "ILimit",
"value": 50
}
]
},
{
"name": "AcroInsanityFactor",
"type": "float32",
"unit": "percent",
"values": [
{
"name": "0",
"value": 0.5
}
]
},
{
"name": "ThrustPIDScaleCurve",
"type": "float32",
"unit": "percent",
"values": [
{
"name": "0",
"value": 0.30000001192092896
},
{
"name": "25",
"value": 0.15000000596046448
},
{
"name": "50",
"value": 0
},
{
"name": "75",
"value": -0.15000000596046448
},
{
"name": "100",
"value": -0.30000001192092896
}
]
},
{
"name": "RollMax",
"type": "uint8",
"unit": "degrees",
"values": [
{
"name": "0",
"value": 55
}
]
},
{
"name": "PitchMax",
"type": "uint8",
"unit": "degrees",
"values": [
{
"name": "0",
"value": 55
}
]
},
{
"name": "YawMax",
"type": "uint8",
"unit": "degrees",
"values": [
{
"name": "0",
"value": 35
}
]
},
{
"name": "StickExpo",
"type": "int8",
"unit": "percent",
"values": [
{
"name": "Roll",
"value": 0
},
{
"name": "Pitch",
"value": 0
},
{
"name": "Yaw",
"value": 0
}
]
},
{
"name": "EnablePiroComp",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "TRUE"
}
]
},
{
"name": "EnableThrustPIDScaling",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "FALSE"
}
]
},
{
"name": "ThrustPIDScaleSource",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "ActuatorDesiredThrust"
}
]
},
{
"name": "ThrustPIDScaleTarget",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "PID"
}
]
},
{
"name": "ThrustPIDScaleAxes",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Roll Pitch"
}
]
}
],
"id": "C02DAA6A",
"instance": 0,
"name": "StabilizationSettingsBank3",
"setting": true
},
{
"fields": [
{
"name": "MaxAccel",
"type": "float32",
"unit": "units/sec",
"values": [
{
"name": "0",
"value": 1000
}
]
},
{
"name": "FeedForward",
"type": "float32",
"unit": "",
"values": [
{
"name": "0",
"value": 0
}
]
},
{
"name": "AccelTime",
"type": "float32",
"unit": "ms",
"values": [
{
"name": "0",
"value": 0
}
]
},
{
"name": "DecelTime",
"type": "float32",
"unit": "ms",
"values": [
{
"name": "0",
"value": 0
}
]
},
{
"name": "ThrottleCurve1",
"type": "float32",
"unit": "percent",
"values": [
{
"name": "0",
"value": 0
},
{
"name": "25",
"value": 0.22499999403953552
},
{
"name": "50",
"value": 0.44999998807907104
},
{
"name": "75",
"value": 0.67499995231628418
},
{
"name": "100",
"value": 0.89999997615814209
}
]
},
{
"name": "ThrottleCurve2",
"type": "float32",
"unit": "percent",
"values": [
{
"name": "0",
"value": 0
},
{
"name": "25",
"value": 0.22499999403953552
},
{
"name": "50",
"value": 0.44999998807907104
},
{
"name": "75",
"value": 0.67499995231628418
},
{
"name": "100",
"value": 0.89999997615814209
}
]
},
{
"name": "MixerValueRoll",
"type": "int8",
"unit": "percent",
"values": [
{
"name": "0",
"value": 50
}
]
},
{
"name": "MixerValuePitch",
"type": "int8",
"unit": "percent",
"values": [
{
"name": "0",
"value": 50
}
]
},
{
"name": "MixerValueYaw",
"type": "int8",
"unit": "percent",
"values": [
{
"name": "0",
"value": 50
}
]
},
{
"name": "Curve2Source",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Throttle"
}
]
},
{
"name": "Mixer1Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Motor"
}
]
},
{
"name": "Mixer1Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 127
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": 64
},
{
"name": "Pitch",
"value": 64
},
{
"name": "Yaw",
"value": -64
}
]
},
{
"name": "Mixer2Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Motor"
}
]
},
{
"name": "Mixer2Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 127
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": -64
},
{
"name": "Pitch",
"value": 64
},
{
"name": "Yaw",
"value": 64
}
]
},
{
"name": "Mixer3Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Motor"
}
]
},
{
"name": "Mixer3Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 127
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": -64
},
{
"name": "Pitch",
"value": -64
},
{
"name": "Yaw",
"value": -64
}
]
},
{
"name": "Mixer4Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Motor"
}
]
},
{
"name": "Mixer4Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 127
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": 64
},
{
"name": "Pitch",
"value": -64
},
{
"name": "Yaw",
"value": 64
}
]
},
{
"name": "Mixer5Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Disabled"
}
]
},
{
"name": "Mixer5Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 0
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": 0
},
{
"name": "Pitch",
"value": 0
},
{
"name": "Yaw",
"value": 0
}
]
},
{
"name": "Mixer6Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Disabled"
}
]
},
{
"name": "Mixer6Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 0
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": 0
},
{
"name": "Pitch",
"value": 0
},
{
"name": "Yaw",
"value": 0
}
]
},
{
"name": "Mixer7Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Disabled"
}
]
},
{
"name": "Mixer7Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 0
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": 0
},
{
"name": "Pitch",
"value": 0
},
{
"name": "Yaw",
"value": 0
}
]
},
{
"name": "Mixer8Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Disabled"
}
]
},
{
"name": "Mixer8Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 0
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": 0
},
{
"name": "Pitch",
"value": 0
},
{
"name": "Yaw",
"value": 0
}
]
},
{
"name": "Mixer9Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Disabled"
}
]
},
{
"name": "Mixer9Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 0
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": 0
},
{
"name": "Pitch",
"value": 0
},
{
"name": "Yaw",
"value": 0
}
]
},
{
"name": "Mixer10Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Disabled"
}
]
},
{
"name": "Mixer10Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 0
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": 0
},
{
"name": "Pitch",
"value": 0
},
{
"name": "Yaw",
"value": 0
}
]
},
{
"name": "Mixer11Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Disabled"
}
]
},
{
"name": "Mixer11Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 0
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": 0
},
{
"name": "Pitch",
"value": 0
},
{
"name": "Yaw",
"value": 0
}
]
},
{
"name": "Mixer12Type",
"type": "enum",
"unit": "",
"values": [
{
"name": "0",
"value": "Disabled"
}
]
},
{
"name": "Mixer12Vector",
"type": "int8",
"unit": "",
"values": [
{
"name": "ThrottleCurve1",
"value": 0
},
{
"name": "ThrottleCurve2",
"value": 0
},
{
"name": "Roll",
"value": 0
},
{
"name": "Pitch",
"value": 0
},
{
"name": "Yaw",
"value": 0
}
]
}
],
"id": "7BF2CFA8",
"instance": 0,
"name": "MixerSettings",
"setting": true
},
{
"fields": [
{
"name": "P",
"type": "float32",
"unit": "1^2",
"values": [
{
"name": "PositionNorth",
"value": 10
},
{
"name": "PositionEast",
"value": 10
},
{
"name": "PositionDown",
"value": 10
},
{
"name": "VelocityNorth",
"value": 1
},
{
"name": "VelocityEast",
"value": 1
},
{
"name": "VelocityDown",
"value": 1
},
{
"name": "AttitudeQ1",
"value": 0.0070000002160668373
},
{
"name": "AttitudeQ2",
"value": 0.0070000002160668373
},
{
"name": "AttitudeQ3",
"value": 0.0070000002160668373
},
{
"name": "AttitudeQ4",
"value": 0.0070000002160668373
},
{
"name": "GyroDriftX",
"value": 9.9999999747524271e-07
},
{
"name": "GyroDriftY",
"value": 9.9999999747524271e-07
},
{
"name": "GyroDriftZ",
"value": 9.9999999747524271e-07
}
]
},
{
"name": "Q",
"type": "float32",
"unit": "1^2",
"values": [
{
"name": "GyroX",
"value": 0.0099999997764825821
},
{
"name": "GyroY",
"value": 0.0099999997764825821
},
{
"name": "GyroZ",
"value": 0.0099999997764825821
},
{
"name": "AccelX",
"value": 0.0099999997764825821
},
{
"name": "AccelY",
"value": 0.0099999997764825821
},
{
"name": "AccelZ",
"value": 0.0099999997764825821
},
{
"name": "GyroDriftX",
"value": 9.9999999747524271e-07
},
{
"name": "GyroDriftY",
"value": 9.9999999747524271e-07
},
{
"name": "GyroDriftZ",
"value": 9.9999999747524271e-07
}
]
},
{
"name": "R",
"type": "float32",
"unit": "1^2",
"values": [
{
"name": "GPSPosNorth",
"value": 1
},
{
"name": "GPSPosEast",
"value": 1
},
{
"name": "GPSPosDown",
"value": 1000000
},
{
"name": "GPSVelNorth",
"value": 0.0010000000474974513
},
{
"name": "GPSVelEast",
"value": 0.0010000000474974513
},
{
"name": "GPSVelDown",
"value": 0.0010000000474974513
},
{
"name": "MagX",
"value": 10
},
{
"name": "MagY",
"value": 10
},
{
"name": "MagZ",
"value": 10
},
{
"name": "BaroZ",
"value": 0.0099999997764825821
}
]
},
{
"name": "FakeR",
"type": "float32",
"unit": "1^2",
"values": [
{
"name": "FakeGPSPosIndoor",
"value": 10
},
{
"name": "FakeGPSVelIndoor",
"value": 1
},
{
"name": "FakeGPSVelAirspeed",
"value": 1000
}
]
}
],
"id": "5E91213C",
"instance": 0,
"name": "EKFConfiguration",
"setting": true
}
],
"owner": "Jim ",
"propeller": "HQ DD 6 X4.5",
"servo": "",
"size": "330",
"subtype": 2,
"type": 1,
"uuid": "{5bf30e57-f44b-427d-bfd6-9e9980c55302}",
"weight": "1003"
}

View File

@ -30,7 +30,7 @@
inkscape:zoom="6.5977991"
inkscape:cx="55.083588"
inkscape:cy="24.071773"
inkscape:current-layer="layer45"
inkscape:current-layer="layer46"
id="namedview3608"
showgrid="true"
inkscape:window-width="1280"
@ -1685,6 +1685,20 @@
ry="0.98050147"
inkscape:label="#rect4550-8-1-4-21-1" />
</g>
<g
inkscape:groupmode="layer"
id="layer46"
inkscape:label="SystemConfiguration-BadThrottleOrCollectiveInputRange">
<rect
style="fill:#d40000;fill-opacity:1;stroke:none;display:inline"
id="SystemConfiguration-BadThrottleOrCollectiveInputRange"
width="13.110236"
height="10.107105"
x="80.806435"
y="51.972187"
ry="0.98050147"
inkscape:label="#rect4550-8-1-4-21-1" />
</g>
<g
inkscape:groupmode="layer"
id="layer43"
@ -3024,7 +3038,7 @@
sodipodi:cy="35.07505"
sodipodi:rx="0.5"
sodipodi:ry="0.5"
d="M 14,35.07505 A 0.5,0.5 0 1 1 13.999725,35.058469"
d="M 14,35.07505 C 14,35.351193 13.776142,35.57505 13.5,35.57505 C 13.223858,35.57505 13,35.351193 13,35.07505 C 13,34.798908 13.223858,34.57505 13.5,34.57505 C 13.769688,34.57505 13.990781,34.78893 13.999725,35.058469"
sodipodi:start="0"
sodipodi:end="6.2500167"
sodipodi:open="true"
@ -3057,7 +3071,7 @@
sodipodi:cy="35.07505"
sodipodi:rx="0.5"
sodipodi:ry="0.5"
d="M 14,35.07505 A 0.5,0.5 0 1 1 13.999725,35.058469"
d="M 14,35.07505 C 14,35.351193 13.776142,35.57505 13.5,35.57505 C 13.223858,35.57505 13,35.351193 13,35.07505 C 13,34.798908 13.223858,34.57505 13.5,34.57505 C 13.769688,34.57505 13.990781,34.78893 13.999725,35.058469"
sodipodi:start="0"
sodipodi:end="6.2500167"
sodipodi:open="true"

Before

Width:  |  Height:  |  Size: 109 KiB

After

Width:  |  Height:  |  Size: 109 KiB

View File

@ -358,7 +358,7 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType)
// rudder
channel = m_aircraft->fwRudder1ChannelBox->currentIndex() - 1;
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127);
// ailerons
channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1;
@ -542,13 +542,13 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType)
// First Vtail servo
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, -pitch);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, yaw);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -yaw);
// Second Vtail servo
channel = m_aircraft->fwElevator2ChannelBox->currentIndex() - 1;
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, pitch);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, yaw);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -yaw);
}
m_aircraft->fwStatusLabel->setText("Mixer generated");

View File

@ -549,6 +549,8 @@ void ConfigInputWidget::wzNext()
// Force flight mode neutral to middle and Throttle neutral at 4%
adjustSpecialNeutrals();
throttleError = false;
checkThrottleRange();
manualSettingsObj->setData(manualSettingsData);
// move to Arming Settings tab
@ -1593,6 +1595,7 @@ void ConfigInputWidget::simpleCalibration(bool enable)
ui->saveRCInputToRAM->setEnabled(false);
ui->saveRCInputToSD->setEnabled(false);
ui->runCalibration->setText(tr("Stop Manual Calibration"));
throttleError = false;
QMessageBox msgBox;
msgBox.setText(tr("<p>Arming Settings are now set to 'Always Disarmed' for your safety.</p>"
@ -1628,11 +1631,6 @@ void ConfigInputWidget::simpleCalibration(bool enable)
connect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject *)), this, SLOT(updateCalibration()));
} else {
ui->configurationWizard->setEnabled(true);
ui->saveRCInputToRAM->setEnabled(true);
ui->saveRCInputToSD->setEnabled(true);
ui->runCalibration->setText(tr("Start Manual Calibration"));
manualCommandData = manualCommandObj->getData();
manualSettingsData = manualSettingsObj->getData();
@ -1641,16 +1639,21 @@ void ConfigInputWidget::simpleCalibration(bool enable)
for (unsigned int i = 0; i < ManualControlCommand::CHANNEL_NUMELEM; i++) {
if ((i == ManualControlSettings::CHANNELNUMBER_FLIGHTMODE) || (i == ManualControlSettings::CHANNELNUMBER_THROTTLE)) {
adjustSpecialNeutrals();
checkThrottleRange();
} else {
manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i];
}
}
manualSettingsObj->setData(manualSettingsData);
// Load actuator settings back from beginning of manual calibration
actuatorSettingsObj->setData(previousActuatorSettingsData);
ui->configurationWizard->setEnabled(true);
ui->saveRCInputToRAM->setEnabled(true);
ui->saveRCInputToSD->setEnabled(true);
ui->runCalibration->setText(tr("Start Manual Calibration"));
disconnect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject *)), this, SLOT(updateCalibration()));
}
}
@ -1671,6 +1674,20 @@ void ConfigInputWidget::adjustSpecialNeutrals()
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]) * 0.04);
}
void ConfigInputWidget::checkThrottleRange()
{
int throttleRange = abs(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE] -
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]);
if (!throttleError && (throttleRange < 300)) {
throttleError = true;
QMessageBox::warning(this, tr("Warning"), tr("<p>There is something wrong with Throttle range. Please redo calibration and move <b>ALL sticks</b>, Throttle stick included.</p>"), QMessageBox::Ok);
// Set Throttle neutral to max value so Throttle can't be positive
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE] =
manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE];
}
}
bool ConfigInputWidget::shouldObjectBeSaved(UAVObject *object)
{
// ManualControlCommand no need to be saved

View File

@ -71,6 +71,7 @@ public:
bool shouldObjectBeSaved(UAVObject *object);
private:
bool throttleError;
bool growing;
bool reverse[ManualControlSettings::CHANNELNEUTRAL_NUMELEM];
txMovements currentMovement;
@ -199,6 +200,7 @@ private slots:
void invertControls();
void simpleCalibration(bool state);
void adjustSpecialNeutrals();
void checkThrottleRange();
void updateCalibration();
void resetChannelSettings();
void resetActuatorSettings();

View File

@ -472,7 +472,7 @@ void ConfigOutputWidget::updateWarnings(UAVObject *)
if (systemAlarms.Alarm[SystemAlarms::ALARM_SYSTEMCONFIGURATION] > SystemAlarms::ALARM_WARNING) {
switch (systemAlarms.ExtendedAlarmStatus[SystemAlarms::EXTENDEDALARMSTATUS_SYSTEMCONFIGURATION]) {
case SystemAlarms::EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT:
setWarning(tr("OneShot only works with Receiver Port settings marked with '+OneShot'<br>"
setWarning(tr("OneShot and PWMSync output only works with Receiver Port settings marked with '+OneShot'<br>"
"When using Receiver Port setting 'PPM_PIN8+OneShot' "
"<b><font color='%1'>Bank %2</font></b> must be set to PWM")
.arg(m_banks.at(3).color().name()).arg(m_banks.at(3).label()->text()));

View File

@ -85,6 +85,15 @@ void EscCalibrationPage::resetAllSecurityCheckboxes()
ui->securityCheckBox3->setChecked(false);
}
int EscCalibrationPage::getHighOutputRate()
{
if (getWizard()->getEscType() == SetupWizard::ESC_ONESHOT) {
return HIGH_ONESHOT125_OUTPUT_PULSE_LENGTH_MICROSECONDS;
} else {
return HIGH_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS;
}
}
void EscCalibrationPage::startButtonClicked()
{
if (!m_isCalibrating) {
@ -95,7 +104,7 @@ void EscCalibrationPage::startButtonClicked()
ui->outputLow->setEnabled(false);
ui->nonconnectedLabel->setEnabled(false);
ui->connectedLabel->setEnabled(true);
ui->outputLevel->setText(QString(tr("%1 µs")).arg(HIGH_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS));
ui->outputLevel->setText(QString(tr("%1 µs")).arg(getHighOutputRate()));
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *uavoManager = pm->getObject<UAVObjectManager>();
Q_ASSERT(uavoManager);
@ -123,7 +132,7 @@ void EscCalibrationPage::startButtonClicked()
}
m_outputUtil.startChannelOutput(m_outputChannels, OFF_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS);
QThread::msleep(100);
m_outputUtil.setChannelOutputValue(HIGH_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS);
m_outputUtil.setChannelOutputValue(getHighOutputRate());
ui->stopButton->setEnabled(true);
}

View File

@ -56,10 +56,12 @@ private:
static const int LOW_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS = 1050;
static const int OFF_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS = 900;
static const int HIGH_PWM_OUTPUT_PULSE_LENGTH_MICROSECONDS = 1900;
static const int HIGH_ONESHOT125_OUTPUT_PULSE_LENGTH_MICROSECONDS = 2000;
Ui::EscCalibrationPage *ui;
bool m_isCalibrating;
OutputCalibrationUtil m_outputUtil;
QList<quint16> m_outputChannels;
int getHighOutputRate();
};
#endif // ESCCALIBRATIONPAGE_H

View File

@ -44,7 +44,7 @@ OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *paren
m_vehicleRenderer = new QSvgRenderer();
// move the code that was here to setupVehicle() so we can determine which image to use.
m_vehicleScene = new QGraphicsScene(this);
m_vehicleScene = new QGraphicsScene(this);
ui->vehicleView->setScene(m_vehicleScene);
}
@ -77,32 +77,32 @@ void OutputCalibrationPage::setupActuatorMinMaxAndNeutral(int motorChannelStart,
for (int servoid = 0; servoid < 12; servoid++) {
if (servoid >= motorChannelStart && servoid <= motorChannelEnd) {
// Set to motor safe values
m_actuatorSettings[servoid].channelMin = 1000;
m_actuatorSettings[servoid].channelNeutral = 1000;
m_actuatorSettings[servoid].channelMax = 1900;
m_actuatorSettings[servoid].channelMin = LOW_OUTPUT_RATE_MILLISECONDS;
m_actuatorSettings[servoid].channelNeutral = LOW_OUTPUT_RATE_MILLISECONDS;
m_actuatorSettings[servoid].channelMax = getHighOutputRate();
m_actuatorSettings[servoid].isReversableMotor = false;
// Car and Tank should use reversable Esc/motors
if ((getWizard()->getVehicleSubType() == SetupWizard::GROUNDVEHICLE_CAR)
|| (getWizard()->getVehicleSubType() == SetupWizard::GROUNDVEHICLE_DIFFERENTIAL)) {
m_actuatorSettings[servoid].channelNeutral = 1500;
m_actuatorSettings[servoid].channelNeutral = NEUTRAL_OUTPUT_RATE_MILLISECONDS;
m_actuatorSettings[servoid].isReversableMotor = true;
// Set initial output value
m_calibrationUtil->startChannelOutput(servoid, 1500);
m_calibrationUtil->startChannelOutput(servoid, NEUTRAL_OUTPUT_RATE_MILLISECONDS);
m_calibrationUtil->stopChannelOutput();
}
} else if (servoid < totalUsedChannels) {
// Set to servo safe values
m_actuatorSettings[servoid].channelMin = 1500;
m_actuatorSettings[servoid].channelNeutral = 1500;
m_actuatorSettings[servoid].channelMax = 1500;
m_actuatorSettings[servoid].channelMin = NEUTRAL_OUTPUT_RATE_MILLISECONDS;
m_actuatorSettings[servoid].channelNeutral = NEUTRAL_OUTPUT_RATE_MILLISECONDS;
m_actuatorSettings[servoid].channelMax = NEUTRAL_OUTPUT_RATE_MILLISECONDS;
// Set initial servo output value
m_calibrationUtil->startChannelOutput(servoid, 1500);
m_calibrationUtil->startChannelOutput(servoid, NEUTRAL_OUTPUT_RATE_MILLISECONDS);
m_calibrationUtil->stopChannelOutput();
} else {
// "Disable" these channels
m_actuatorSettings[servoid].channelMin = 1000;
m_actuatorSettings[servoid].channelNeutral = 1000;
m_actuatorSettings[servoid].channelMax = 1000;
m_actuatorSettings[servoid].channelMin = LOW_OUTPUT_RATE_MILLISECONDS;
m_actuatorSettings[servoid].channelNeutral = LOW_OUTPUT_RATE_MILLISECONDS;
m_actuatorSettings[servoid].channelMax = LOW_OUTPUT_RATE_MILLISECONDS;
}
}
}
@ -216,7 +216,7 @@ void OutputCalibrationPage::setupVehicle()
case SetupWizard::FIXED_WING_AILERON:
loadSVGFile(FIXEDWING_SVG_FILE);
m_wizardIndexes << 0 << 1 << 2 << 2 << 2;
m_vehicleElementIds << "aileron-single" << "ail2-frame" << "ail2-motor" << "ail2-aileron" << "ail2-elevator" << "ail2-rudder";
m_vehicleElementIds << "singleaileron" << "singleaileron-frame" << "singleaileron-motor" << "singleaileron-aileron" << "singleaileron-elevator" << "singleaileron-rudder";
m_vehicleElementTypes << FULL << FRAME << MOTOR << SERVO << SERVO << SERVO;
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4;
m_channelIndex << 0 << 2 << 0 << 1 << 3;
@ -298,6 +298,7 @@ void OutputCalibrationPage::setupVehicle()
void OutputCalibrationPage::setupVehicleItems()
{
m_vehicleItems.clear();
m_arrowsItems.clear();
m_vehicleBoundsItem = new QGraphicsSvgItem();
m_vehicleBoundsItem->setSharedRenderer(m_vehicleRenderer);
m_vehicleBoundsItem->setElementId(m_vehicleElementIds[0]);
@ -319,6 +320,46 @@ void OutputCalibrationPage::setupVehicleItems()
m_vehicleScene->addItem(item);
m_vehicleItems << item;
bool addArrows = false;
if ((m_vehicleElementIds[i].contains("left")) || (m_vehicleElementIds[i].contains("right"))
|| (m_vehicleElementIds[i].contains("elevator")) || (m_vehicleElementIds[i].contains("rudder"))
|| (m_vehicleElementIds[i].contains("steering")) || (m_vehicleElementIds[i] == "singleaileron-aileron")) {
addArrows = true;
}
if (addArrows) {
QString arrowUp = "-up"; // right if rudder / steering
QString arrowDown = "-down"; // left
QGraphicsSvgItem *itemUp = new QGraphicsSvgItem();
itemUp->setSharedRenderer(m_vehicleRenderer);
QString elementUp = m_vehicleElementIds[i] + arrowUp;
itemUp->setElementId(elementUp);
itemUp->setZValue(i + 10);
itemUp->setOpacity(0);
QRectF itemBounds = m_vehicleRenderer->boundsOnElement(elementUp);
itemUp->setPos(itemBounds.x() - parentBounds.x(), itemBounds.y() - parentBounds.y());
m_vehicleScene->addItem(itemUp);
m_arrowsItems << itemUp;
QGraphicsSvgItem *itemDown = new QGraphicsSvgItem();
itemDown->setSharedRenderer(m_vehicleRenderer);
QString elementDown = m_vehicleElementIds[i] + arrowDown;
itemDown->setElementId(elementDown);
itemDown->setZValue(i + 10);
itemDown->setOpacity(0);
itemBounds = m_vehicleRenderer->boundsOnElement(elementDown);
itemDown->setPos(itemBounds.x() - parentBounds.x(), itemBounds.y() - parentBounds.y());
m_vehicleScene->addItem(itemDown);
m_arrowsItems << itemDown;
}
}
}
@ -345,6 +386,24 @@ void OutputCalibrationPage::setupVehicleHighlightedPart()
}
}
void OutputCalibrationPage::showElementMovement(bool isUp, qreal value)
{
QString highlightedItemName = m_vehicleItems[m_currentWizardIndex]->elementId();
for (int i = 0; i < m_arrowsItems.size(); i++) {
QString upItemName = highlightedItemName + "-up";
QString downItemName = highlightedItemName + "-down";
if (m_arrowsItems[i]->elementId() == upItemName) {
QGraphicsSvgItem *itemUp = m_arrowsItems[i];
itemUp->setOpacity(isUp ? value : 0);
}
if (m_arrowsItems[i]->elementId() == downItemName) {
QGraphicsSvgItem *itemDown = m_arrowsItems[i];
itemDown->setOpacity(isUp ? 0 : value);
}
}
}
void OutputCalibrationPage::setWizardPage()
{
qDebug() << "Wizard index: " << m_currentWizardIndex;
@ -390,6 +449,9 @@ void OutputCalibrationPage::setWizardPage()
}
}
setupVehicleHighlightedPart();
// Hide arrows
showElementMovement(true, 0);
showElementMovement(false, 0);
}
void OutputCalibrationPage::initializePage()
@ -551,6 +613,9 @@ void OutputCalibrationPage::enableServoSliders(bool enabled)
ui->servoMinAngleSlider->setEnabled(enabled);
ui->servoMaxAngleSlider->setEnabled(enabled);
ui->reverseCheckbox->setEnabled(!enabled);
// Hide arrows
showElementMovement(true, 0);
showElementMovement(false, 0);
}
bool OutputCalibrationPage::checkAlarms()
@ -595,6 +660,15 @@ void OutputCalibrationPage::debugLogChannelValues()
qDebug() << "ChannelMax : " << m_actuatorSettings[currentChannel].channelMax;
}
int OutputCalibrationPage::getHighOutputRate()
{
if (getWizard()->getEscType() == SetupWizard::ESC_ONESHOT) {
return HIGH_OUTPUT_RATE_MILLISECONDS_ONESHOT125;
} else {
return HIGH_OUTPUT_RATE_MILLISECONDS_PWM;
}
}
void OutputCalibrationPage::on_motorNeutralSlider_valueChanged(int value)
{
Q_UNUSED(value);
@ -654,6 +728,27 @@ void OutputCalibrationPage::on_servoCenterAngleSlider_valueChanged(int position)
ui->servoMaxAngleSlider->setValue(value);
}
}
quint16 minValue = (ui->reverseCheckbox->isChecked()) ? ui->servoMaxAngleSlider->value() : ui->servoMinAngleSlider->value();
quint16 maxValue = (ui->reverseCheckbox->isChecked()) ? ui->servoMinAngleSlider->value() : ui->servoMaxAngleSlider->value();
quint16 range = maxValue - minValue;
// Reset arows
showElementMovement(true, 0);
showElementMovement(false, 0);
// 30% "Dead band" : no arrow display
quint16 limitLow = minValue + (range * 0.35);
quint16 limitHigh = maxValue - (range * 0.35);
quint16 middle = minValue + (range / 2);
qreal arrowOpacity = 0;
if (value < limitLow) {
arrowOpacity = (qreal)(middle - value) / (qreal)(middle - minValue);
showElementMovement(ui->reverseCheckbox->isChecked(), arrowOpacity);
} else if (value > limitHigh) {
arrowOpacity = (qreal)(value - middle) / (qreal)(maxValue - middle);
showElementMovement(!ui->reverseCheckbox->isChecked(), arrowOpacity);
}
debugLogChannelValues();
}
@ -666,8 +761,8 @@ void OutputCalibrationPage::on_servoMinAngleSlider_valueChanged(int position)
QList<quint16> currentChannels;
getCurrentChannels(currentChannels);
quint16 currentChannel = currentChannels[0];
m_actuatorSettings[currentChannel].channelMin = value;
ui->servoPWMValue->setText(tr("Output value : <b>%1</b> µs (Min)").arg(value));
// Adjust neutral and max
if (ui->reverseCheckbox->isChecked()) {
@ -697,8 +792,8 @@ void OutputCalibrationPage::on_servoMaxAngleSlider_valueChanged(int position)
QList<quint16> currentChannels;
getCurrentChannels(currentChannels);
quint16 currentChannel = currentChannels[0];
m_actuatorSettings[currentChannel].channelMax = value;
ui->servoPWMValue->setText(tr("Output value : <b>%1</b> µs (Max)").arg(value));
// Adjust neutral and min
if (ui->reverseCheckbox->isChecked()) {

View File

@ -74,10 +74,16 @@ private slots:
private:
enum ElementType { FULL, FRAME, MOTOR, SERVO };
static const int LOW_OUTPUT_RATE_MILLISECONDS = 1000;
static const int NEUTRAL_OUTPUT_RATE_MILLISECONDS = 1500;
static const int HIGH_OUTPUT_RATE_MILLISECONDS_PWM = 1900;
static const int HIGH_OUTPUT_RATE_MILLISECONDS_ONESHOT125 = 2000;
void setupVehicle();
void startWizard();
void setupVehicleItems();
void setupVehicleHighlightedPart();
void showElementMovement(bool isUp, qreal value);
void setWizardPage();
void enableButtons(bool enable);
void enableServoSliders(bool enabled);
@ -85,8 +91,11 @@ private:
quint16 value, quint16 safeValue, QSlider *slider);
bool checkAlarms();
void debugLogChannelValues();
void getCurrentChannels(QList<quint16> &channels);
void enableAllMotorsCheckBox(bool enable);
int getHighOutputRate();
quint16 getCurrentChannel();
Ui::OutputCalibrationPage *ui;
QSvgRenderer *m_vehicleRenderer;
@ -98,6 +107,7 @@ private:
QList<QString> m_vehicleElementIds;
QList<ElementType> m_vehicleElementTypes;
QList<QGraphicsSvgItem *> m_vehicleItems;
QList<QGraphicsSvgItem *> m_arrowsItems;
QList<quint16> m_vehicleHighlightElementIndexes;
QList<quint16> m_channelIndex;
QList<quint16> m_wizardIndexes;

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 422 KiB

After

Width:  |  Height:  |  Size: 526 KiB

View File

@ -26,7 +26,7 @@
inkscape:export-ydpi="70.479134"><metadata
id="metadata4103"><rdf:RDF><cc:Work
rdf:about=""><dc:format>image/svg+xml</dc:format><dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title /></cc:Work></rdf:RDF></metadata><defs
rdf:resource="http://purl.org/dc/dcmitype/StillImage" /><dc:title></dc:title></cc:Work></rdf:RDF></metadata><defs
id="defs4101"><radialGradient
gradientUnits="userSpaceOnUse"
gradientTransform="matrix(-98.0973,98.0973,-98.0973,-98.0973,-113082.84,-155604.09)"
@ -7564,7 +7564,19 @@
id="stop5573-2-8-5-9-5-0-9-4" /><stop
style="stop-color:#848081;stop-opacity:1"
offset="1"
id="stop5575-5-7-9-0-2-8-2-3" /></linearGradient></defs><sodipodi:namedview
id="stop5575-5-7-9-0-2-8-2-3" /></linearGradient><filter
color-interpolation-filters="sRGB"
inkscape:collect="always"
id="filter9921-4-2"><feGaussianBlur
inkscape:collect="always"
stdDeviation="0.60884705"
id="feGaussianBlur9923-3-3" /></filter><filter
color-interpolation-filters="sRGB"
inkscape:collect="always"
id="filter9921-4-2-6-0"><feGaussianBlur
inkscape:collect="always"
stdDeviation="0.60884705"
id="feGaussianBlur9923-3-3-3-2" /></filter></defs><sodipodi:namedview
pagecolor="#ffffff"
bordercolor="#666666"
borderopacity="1"
@ -7577,13 +7589,13 @@
inkscape:window-height="928"
id="namedview4099"
showgrid="false"
inkscape:zoom="0.78435941"
inkscape:cx="421.0109"
inkscape:cy="573.46538"
inkscape:zoom="0.40567848"
inkscape:cx="743.97136"
inkscape:cy="255.67352"
inkscape:window-x="0"
inkscape:window-y="27"
inkscape:window-maximized="1"
inkscape:current-layer="car-steering"
inkscape:current-layer="motorbike"
showborder="true"
inkscape:showpageshadow="false"
showguides="true"
@ -7600,7 +7612,7 @@
fit-margin-top="50"
fit-margin-bottom="50"
fit-margin-right="50"
inkscape:bbox-nodes="false"
inkscape:bbox-nodes="true"
inkscape:snap-object-midpoints="true"
inkscape:snap-midpoints="true"
inkscape:snap-grids="false"><inkscape:grid
@ -7771,7 +7783,7 @@
style="display:inline"
transform="translate(-1.0465068e-7,-4.4182544e-5)"><path
transform="matrix(-1,0,0,1,681.77091,708.1928)"
d="M 191.31786,1225.9447 A 95.658928,20.138721 0 1 1 0,1225.9447 A 95.658928,20.138721 0 1 1 191.31786,1225.9447 z"
d="M 191.31786,1225.9447 C 191.31786,1237.067 148.48989,1246.0834 95.658928,1246.0834 C 42.827961,1246.0834 0,1237.067 0,1225.9447 C 0,1214.8224 42.827961,1205.806 95.658928,1205.806 C 148.48989,1205.806 191.31786,1214.8224 191.31786,1225.9447 z"
sodipodi:ry="20.138721"
sodipodi:rx="95.658928"
sodipodi:cy="1225.9447"
@ -7836,7 +7848,7 @@
x="300.95084"
y="1906.3666" /><path
transform="translate(-0.00459003,-104.83732)"
d="M 314.66354,2090.5566 A 4.9847689,4.5971303 0 1 1 304.694,2090.5566 A 4.9847689,4.5971303 0 1 1 314.66354,2090.5566 z"
d="M 314.66354,2090.5566 C 314.66354,2093.0956 312.43178,2095.1538 309.67877,2095.1538 C 306.92576,2095.1538 304.694,2093.0956 304.694,2090.5566 C 304.694,2088.0177 306.92576,2085.9595 309.67877,2085.9595 C 312.43178,2085.9595 314.66354,2088.0177 314.66354,2090.5566 z"
sodipodi:ry="4.5971303"
sodipodi:rx="4.9847689"
sodipodi:cy="2090.5566"
@ -7860,7 +7872,7 @@
sodipodi:cy="-54.65202"
sodipodi:rx="7.9385705"
sodipodi:ry="7.9385705"
d="M 154.44129,-54.65202 A 7.9385705,7.9385705 0 1 1 138.56415,-54.65202 A 7.9385705,7.9385705 0 1 1 154.44129,-54.65202 z"
d="M 154.44129,-54.65202 C 154.44129,-50.267668 150.88707,-46.713449 146.50272,-46.713449 C 142.11836,-46.713449 138.56415,-50.267668 138.56415,-54.65202 C 138.56415,-59.036371 142.11836,-62.59059 146.50272,-62.59059 C 150.88707,-62.59059 154.44129,-59.036371 154.44129,-54.65202 z"
transform="matrix(-0.81878721,0,0,0.81878721,565.51334,1690.0415)" /><g
style="display:inline"
transform="matrix(-0.39813496,-0.91732685,-0.91732685,0.39813496,1757.6809,1391.2077)"
@ -7960,7 +7972,7 @@
sodipodi:cy="1225.9447"
sodipodi:rx="95.658928"
sodipodi:ry="20.138721"
d="M 191.31786,1225.9447 A 95.658928,20.138721 0 1 1 0,1225.9447 A 95.658928,20.138721 0 1 1 191.31786,1225.9447 z"
d="M 191.31786,1225.9447 C 191.31786,1237.067 148.48989,1246.0834 95.658928,1246.0834 C 42.827961,1246.0834 0,1237.067 0,1225.9447 C 0,1214.8224 42.827961,1205.806 95.658928,1205.806 C 148.48989,1205.806 191.31786,1214.8224 191.31786,1225.9447 z"
transform="matrix(-1,0,0,1,243.77091,708.1928)" /><g
style="display:inline"
id="g5488"
@ -7975,7 +7987,7 @@
id="path5494"
inkscape:connector-curvature="0" /></g><path
transform="matrix(-2.5815325,0,0,2.5815325,1310.6966,-3004.1641)"
d="M 464.20661,1875.9762 A 12.461923,12.461923 0 1 1 439.28277,1875.9762 A 12.461923,12.461923 0 1 1 464.20661,1875.9762 z"
d="M 464.20661,1875.9762 C 464.20661,1882.8587 458.62722,1888.4381 451.74469,1888.4381 C 444.86216,1888.4381 439.28277,1882.8587 439.28277,1875.9762 C 439.28277,1869.0937 444.86216,1863.5143 451.74469,1863.5143 C 458.62722,1863.5143 464.20661,1869.0937 464.20661,1875.9762 z"
sodipodi:ry="12.461923"
sodipodi:rx="12.461923"
sodipodi:cy="1875.9762"
@ -8021,7 +8033,7 @@
style="display:inline"
id="motorbike-m1"><path
transform="matrix(1.1648161,0,0,1.1648161,-71.612697,-316.94008)"
d="M 428.06704,1876.2877 A 27.727777,27.727777 0 1 1 372.61149,1876.2877 A 27.727777,27.727777 0 1 1 428.06704,1876.2877 z"
d="M 428.06704,1876.2877 C 428.06704,1891.6013 415.65289,1904.0155 400.33926,1904.0155 C 385.02564,1904.0155 372.61149,1891.6013 372.61149,1876.2877 C 372.61149,1860.9741 385.02564,1848.5599 400.33926,1848.5599 C 415.65289,1848.5599 428.06704,1860.9741 428.06704,1876.2877 z"
sodipodi:ry="27.727777"
sodipodi:rx="27.727777"
sodipodi:cy="1876.2877"
@ -8036,7 +8048,7 @@
sodipodi:cy="1876.2877"
sodipodi:rx="27.727777"
sodipodi:ry="27.727777"
d="M 428.06704,1876.2877 A 27.727777,27.727777 0 1 1 372.61149,1876.2877 A 27.727777,27.727777 0 1 1 428.06704,1876.2877 z"
d="M 428.06704,1876.2877 C 428.06704,1891.6013 415.65289,1904.0155 400.33926,1904.0155 C 385.02564,1904.0155 372.61149,1891.6013 372.61149,1876.2877 C 372.61149,1860.9741 385.02564,1848.5599 400.33926,1848.5599 C 415.65289,1848.5599 428.06704,1860.9741 428.06704,1876.2877 z"
transform="matrix(1.1409811,0,0,1.1409811,-62.070587,-272.21865)" /><g
transform="matrix(-1,0,0,1,789.41785,0)"
id="text5535"
@ -8069,7 +8081,31 @@
style="fill:#ffffff"
inkscape:connector-curvature="0"
d="M 403.899,769.674 V 771.895 H 391.461 C 391.443,771.339 391.534,770.804 391.73,770.291 C 392.047,769.444 392.554,768.609 393.251,767.789 C 393.949,766.967 394.956,766.018 396.274,764.939 C 398.319,763.259 399.7,761.931 400.419,760.954 C 401.139,759.975 401.498,759.049 401.498,758.176 C 401.498,757.26 401.17,756.488 400.517,755.862 C 399.863,755.232 399.008,754.918 397.955,754.918 C 396.843,754.918 395.953,755.252 395.285,755.919 C 394.618,756.587 394.28,757.511 394.271,758.691 L 391.896,758.448 C 392.059,756.677 392.67,755.327 393.731,754.398 C 394.792,753.467 396.217,753.003 398.005,753.003 C 399.81,753.003 401.238,753.504 402.291,754.505 C 403.344,755.506 403.869,756.746 403.869,758.227 C 403.869,758.982 403.717,759.719 403.408,760.45 C 403.097,761.177 402.588,761.942 401.873,762.747 C 401.16,763.552 399.974,764.655 398.311,766.059 C 396.924,767.222 396.036,768.011 395.643,768.426 C 395.25,768.841 394.924,769.258 394.667,769.677 L 403.899,769.674 L 403.899,769.674 z"
id="path16338" /></g></g></g></g><g
id="path16338" /></g></g></g><g
transform="matrix(0.93030357,-0.36679049,0.36679049,0.93030357,-370.03515,332.30549)"
id="motorbike-steering-down"><path
style="color:#000000;fill:#1b421b;fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:0.5;marker:none;visibility:visible;display:inline;overflow:visible;filter:url(#filter9921-4-2-6-0);enable-background:accumulate"
d="M 530.37305,1424.5117 L 518.07691,1425.5117 L 540.78076,1398.5117 L 563.48462,1425.5117 L 551.18848,1424.5117 L 551.18848,1474.8734 L 530.37305,1474.8734 z"
id="path11299-8"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cccccccc"
transform="matrix(0,1,-1,0,1803.5344,1015.8512)" /><path
style="color:#000000;fill:#1bb81b;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:0.5;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate"
d="M 379.03125,1535.9062 L 380.03125,1548.2188 L 329.65625,1548.2188 L 329.65625,1569.0312 L 380.03125,1569.0312 L 379.03125,1581.3438 L 406.03125,1558.625 L 379.03125,1535.9062 z M 354.84375,1551.4062 C 356.21255,1551.4062 357.30371,1551.7372 358.125,1552.4375 C 358.95264,1553.1314 359.48318,1554.1503 359.71875,1555.5 L 357.4375,1556.0312 C 357.26559,1555.3121 356.95838,1554.757 356.5,1554.375 C 356.0416,1553.993 355.4804,1553.8125 354.84375,1553.8125 C 353.85693,1553.8125 353.07994,1554.1985 352.46875,1554.9688 C 351.85756,1555.7325 351.53125,1556.8963 351.53125,1558.4688 C 351.53125,1560.1556 351.86913,1561.4339 352.53125,1562.3125 C 353.09787,1563.0701 353.87603,1563.4687 354.84375,1563.4688 C 355.29577,1563.4688 355.76614,1563.3351 356.25,1563.125 C 356.74022,1562.9086 357.14925,1562.6192 357.53125,1562.25 L 357.53125,1560.5 L 354.875,1560.5 L 354.875,1558.125 L 359.875,1558.125 L 359.875,1563.7188 C 359.37204,1564.3106 358.67314,1564.7922 357.75,1565.2188 C 356.82685,1565.645 355.89826,1565.875 354.96875,1565.875 C 353.8355,1565.875 352.8346,1565.585 351.96875,1565.0312 C 351.1029,1564.4712 350.41557,1563.639 349.90625,1562.5312 C 349.40329,1561.4174 349.15625,1560.1276 349.15625,1558.625 C 349.15625,1557.0844 349.39692,1555.7513 349.90625,1554.6562 C 350.42194,1553.5615 351.09133,1552.7597 351.90625,1552.2188 C 352.72752,1551.6777 353.70414,1551.4062 354.84375,1551.4062 z M 333.5,1551.625 L 338.375,1551.625 C 339.62284,1551.6251 340.5277,1551.7454 341.0625,1552 C 341.59728,1552.2483 342.0312,1552.6886 342.375,1553.3125 C 342.71878,1553.93 342.90624,1554.6966 342.90625,1555.5625 C 342.90624,1556.6575 342.62217,1557.519 342.09375,1558.1875 C 341.57169,1558.8559 340.84271,1559.2969 339.875,1559.4688 C 340.37158,1559.8253 340.76904,1560.1984 341.09375,1560.625 C 341.41843,1561.0451 341.87723,1561.8113 342.4375,1562.9062 L 343.8125,1565.625 L 341.0625,1565.625 L 339.375,1562.5938 C 338.77018,1561.4924 338.37271,1560.805 338.15625,1560.5312 C 337.93978,1560.2512 337.71068,1560.0394 337.46875,1559.9375 C 337.22682,1559.8293 336.84728,1559.7813 336.3125,1559.7812 L 335.8125,1559.7812 L 335.8125,1565.625 L 333.5,1565.625 L 333.5,1551.625 z M 345,1551.625 L 347.3125,1551.625 L 347.3125,1565.625 L 345,1565.625 L 345,1551.625 z M 362.03125,1551.625 L 364.34375,1551.625 L 364.34375,1557.1562 L 368.90625,1557.1562 L 368.90625,1551.625 L 371.21875,1551.625 L 371.21875,1565.625 L 368.90625,1565.625 L 368.90625,1559.5 L 364.34375,1559.5 L 364.34375,1565.625 L 362.03125,1565.625 L 362.03125,1551.625 z M 372.78125,1551.625 L 381.90625,1551.625 L 381.90625,1554 L 378.5,1554 L 378.5,1565.625 L 376.1875,1565.625 L 376.1875,1554 L 372.78125,1554 L 372.78125,1551.625 z M 335.8125,1554 L 335.8125,1557.5625 L 337.53125,1557.5625 C 338.58172,1557.5625 339.24475,1557.4954 339.53125,1557.4062 C 339.81774,1557.3108 340.07173,1557.1238 340.25,1556.8438 C 340.42826,1556.5637 340.49999,1556.2147 340.5,1555.75 C 340.49999,1555.3043 340.42826,1554.9236 340.25,1554.6562 C 340.07173,1554.3825 339.80559,1554.1956 339.5,1554.0938 C 339.28353,1554.0238 338.66274,1554 337.625,1554 L 335.8125,1554 z"
id="path11301-5"
inkscape:connector-curvature="0" /></g><g
transform="matrix(0.93030357,-0.36679049,0.36679049,0.93030357,-364.52913,330.13459)"
id="motorbike-steering-up"><path
transform="matrix(0,1,1,0,-1157.8507,1015.8512)"
sodipodi:nodetypes="cccccccc"
inkscape:connector-curvature="0"
id="path11305-8"
d="M 530.37305,1424.5117 L 518.07691,1425.5117 L 540.78076,1398.5117 L 563.48462,1425.5117 L 551.18848,1424.5117 L 551.18848,1474.8734 L 530.37305,1474.8734 z"
style="color:#000000;fill:#1b421b;fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:0.5;marker:none;visibility:visible;display:inline;overflow:visible;filter:url(#filter9921-4-2-6-0);enable-background:accumulate" /><path
style="color:#000000;fill:#1bb81b;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:0.5;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate"
d="M 266.65625,1535.9062 L 239.65625,1558.625 L 266.65625,1581.3438 L 265.65625,1569.0312 L 316.03125,1569.0312 L 316.03125,1548.2188 L 265.65625,1548.2188 L 266.65625,1535.9062 z M 283.3125,1551.625 L 291.84375,1551.625 L 291.84375,1554 L 285.625,1554 L 285.625,1557.0938 L 291.40625,1557.0938 L 291.40625,1559.4688 L 285.625,1559.4688 L 285.625,1563.2812 L 292.03125,1563.2812 L 292.03125,1565.625 L 283.3125,1565.625 L 283.3125,1551.625 z M 294.03125,1551.625 L 301.875,1551.625 L 301.875,1554 L 296.34375,1554 L 296.34375,1557.3125 L 301.125,1557.3125 L 301.125,1559.6875 L 296.34375,1559.6875 L 296.34375,1565.625 L 294.03125,1565.625 L 294.03125,1551.625 z M 303,1551.625 L 312.125,1551.625 L 312.125,1554 L 308.71875,1554 L 308.71875,1565.625 L 306.40625,1565.625 L 306.40625,1554 L 303,1554 L 303,1551.625 z M 273.5625,1551.75 L 275.875,1551.75 L 275.875,1563.2812 L 281.625,1563.2812 L 281.625,1565.625 L 273.5625,1565.625 L 273.5625,1551.75 z"
id="path11307-7"
inkscape:connector-curvature="0" /></g></g><g
id="tank"><g
id="tank-frame"><path
sodipodi:nodetypes="sssssssss"
@ -8104,7 +8140,7 @@
id="g4317-6"
transform="translate(-23.155453,-40.626099)"><path
transform="translate(49.34375,1674.1645)"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
sodipodi:ry="19.124739"
sodipodi:rx="19.124739"
sodipodi:cy="-643.0614"
@ -8119,7 +8155,7 @@
sodipodi:cy="-643.0614"
sodipodi:rx="19.124739"
sodipodi:ry="19.124739"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
transform="matrix(0.29043923,0,0,0.29043923,178.13229,1217.8734)" /></g><g
transform="translate(58.844547,-40.626099)"
id="g4323-1"><path
@ -8130,10 +8166,10 @@
sodipodi:cy="-643.0614"
sodipodi:rx="19.124739"
sodipodi:ry="19.124739"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
transform="translate(49.34375,1674.1645)" /><path
transform="matrix(0.29043923,0,0,0.29043923,178.13229,1217.8734)"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
sodipodi:ry="19.124739"
sodipodi:rx="19.124739"
sodipodi:cy="-643.0614"
@ -8144,7 +8180,7 @@
id="g4329-9"
transform="translate(142.84455,-40.626099)"><path
transform="translate(49.34375,1674.1645)"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
sodipodi:ry="19.124739"
sodipodi:rx="19.124739"
sodipodi:cy="-643.0614"
@ -8159,7 +8195,7 @@
sodipodi:cy="-643.0614"
sodipodi:rx="19.124739"
sodipodi:ry="19.124739"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
transform="matrix(0.29043923,0,0,0.29043923,178.13229,1217.8734)" /></g><g
transform="translate(222.84455,-40.626099)"
id="g4335-3"><path
@ -8170,10 +8206,10 @@
sodipodi:cy="-643.0614"
sodipodi:rx="19.124739"
sodipodi:ry="19.124739"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
transform="translate(49.34375,1674.1645)" /><path
transform="matrix(0.29043923,0,0,0.29043923,178.13229,1217.8734)"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
sodipodi:ry="19.124739"
sodipodi:rx="19.124739"
sodipodi:cy="-643.0614"
@ -8193,10 +8229,10 @@
sodipodi:cy="-643.0614"
sodipodi:rx="19.124739"
sodipodi:ry="19.124739"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
transform="translate(49.34375,1674.1645)" /><path
transform="matrix(0.29043923,0,0,0.29043923,178.13229,1217.8734)"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
sodipodi:ry="19.124739"
sodipodi:rx="19.124739"
sodipodi:cy="-643.0614"
@ -8207,7 +8243,7 @@
id="g4349-6"
transform="translate(58.844547,-40.626099)"><path
transform="translate(49.34375,1674.1645)"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
sodipodi:ry="19.124739"
sodipodi:rx="19.124739"
sodipodi:cy="-643.0614"
@ -8222,7 +8258,7 @@
sodipodi:cy="-643.0614"
sodipodi:rx="19.124739"
sodipodi:ry="19.124739"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
transform="matrix(0.29043923,0,0,0.29043923,178.13229,1217.8734)" /></g><g
transform="translate(142.84455,-40.626099)"
id="g4355-2"><path
@ -8233,10 +8269,10 @@
sodipodi:cy="-643.0614"
sodipodi:rx="19.124739"
sodipodi:ry="19.124739"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
transform="translate(49.34375,1674.1645)" /><path
transform="matrix(0.29043923,0,0,0.29043923,178.13229,1217.8734)"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
sodipodi:ry="19.124739"
sodipodi:rx="19.124739"
sodipodi:cy="-643.0614"
@ -8247,7 +8283,7 @@
id="g4361-2"
transform="translate(222.84455,-40.626099)"><path
transform="translate(49.34375,1674.1645)"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
sodipodi:ry="19.124739"
sodipodi:rx="19.124739"
sodipodi:cy="-643.0614"
@ -8262,7 +8298,7 @@
sodipodi:cy="-643.0614"
sodipodi:rx="19.124739"
sodipodi:ry="19.124739"
d="M 200.62933,-643.0614 A 19.124739,19.124739 0 1 1 162.37985,-643.0614 A 19.124739,19.124739 0 1 1 200.62933,-643.0614 z"
d="M 200.62933,-643.0614 C 200.62933,-632.4991 192.06689,-623.93666 181.50459,-623.93666 C 170.94229,-623.93666 162.37985,-632.4991 162.37985,-643.0614 C 162.37985,-653.6237 170.94229,-662.18614 181.50459,-662.18614 C 192.06689,-662.18614 200.62933,-653.6237 200.62933,-643.0614 z"
transform="matrix(0.29043923,0,0,0.29043923,178.13229,1217.8734)" /></g></g><path
transform="translate(1.5175692e-7,-3.7640998e-6)"
style="color:#000000;fill:url(#linearGradient16164);fill-opacity:1;fill-rule:nonzero;stroke:#131715;stroke-width:0.31890565;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate"
@ -9044,7 +9080,7 @@
sodipodi:cy="1901.3416"
sodipodi:rx="0.92891532"
sodipodi:ry="0.92891532"
d="M 48.904387,1901.3416 A 0.92891532,0.92891532 0 1 1 47.046556,1901.3416 A 0.92891532,0.92891532 0 1 1 48.904387,1901.3416 z"
d="M 48.904387,1901.3416 C 48.904387,1901.8546 48.488497,1902.2705 47.975471,1902.2705 C 47.462446,1902.2705 47.046556,1901.8546 47.046556,1901.3416 C 47.046556,1900.8285 47.462446,1900.4126 47.975471,1900.4126 C 48.488497,1900.4126 48.904387,1900.8285 48.904387,1901.3416 z"
transform="matrix(-3.6465408,0,0,3.6465408,671.05978,-4564.7251)" /><path
d="M 649.1838,2260.3441 C 660.1028,2271.2721 660.1028,2288.9881 649.1708,2299.9081 C 638.2498,2310.8331 620.5338,2310.8331 609.6078,2299.9081 C 598.6868,2288.9871 598.6868,2271.2751 609.6178,2260.3531 C 620.5388,2249.4271 638.2528,2249.4251 649.1828,2260.3421"
id="path16350"
@ -9056,7 +9092,31 @@
style="fill:#ffffff"
inkscape:connector-curvature="0"
d="M 252.11,629.086 H 249.801 V 614.363 C 249.244,614.892 248.516,615.425 247.612,615.955 C 246.71,616.486 245.899,616.884 245.18,617.148 V 614.916 C 246.471,614.309 247.601,613.572 248.569,612.708 C 249.536,611.844 250.219,611.006 250.622,610.192 H 252.11 V 629.086 z"
id="path16354" /></g></g></g></g><g
id="path16354" /></g></g><g
transform="matrix(0,0.99999999,-0.99999999,0,2291.2542,2043.3476)"
id="car-steering-up"><path
style="color:#000000;fill:#1b421b;fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:0.5;marker:none;visibility:visible;display:inline;overflow:visible;filter:url(#filter9921-4-2);enable-background:accumulate"
d="M 530.37305,1424.5117 L 518.07691,1425.5117 L 540.78076,1398.5117 L 563.48462,1425.5117 L 551.18848,1424.5117 L 551.18848,1474.8734 L 530.37305,1474.8734 z"
id="path11299"
inkscape:connector-curvature="0"
sodipodi:nodetypes="cccccccc"
transform="matrix(0,1,-1,0,1803.5344,1015.8512)" /><path
style="color:#000000;fill:#1bb81b;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:0.5;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate"
d="M 379.03125,1535.9062 L 380.03125,1548.2188 L 329.65625,1548.2188 L 329.65625,1569.0312 L 380.03125,1569.0312 L 379.03125,1581.3438 L 406.03125,1558.625 L 379.03125,1535.9062 z M 354.84375,1551.4062 C 356.21255,1551.4062 357.30371,1551.7372 358.125,1552.4375 C 358.95264,1553.1314 359.48318,1554.1503 359.71875,1555.5 L 357.4375,1556.0312 C 357.26559,1555.3121 356.95838,1554.757 356.5,1554.375 C 356.0416,1553.993 355.4804,1553.8125 354.84375,1553.8125 C 353.85693,1553.8125 353.07994,1554.1985 352.46875,1554.9688 C 351.85756,1555.7325 351.53125,1556.8963 351.53125,1558.4688 C 351.53125,1560.1556 351.86913,1561.4339 352.53125,1562.3125 C 353.09787,1563.0701 353.87603,1563.4687 354.84375,1563.4688 C 355.29577,1563.4688 355.76614,1563.3351 356.25,1563.125 C 356.74022,1562.9086 357.14925,1562.6192 357.53125,1562.25 L 357.53125,1560.5 L 354.875,1560.5 L 354.875,1558.125 L 359.875,1558.125 L 359.875,1563.7188 C 359.37204,1564.3106 358.67314,1564.7922 357.75,1565.2188 C 356.82685,1565.645 355.89826,1565.875 354.96875,1565.875 C 353.8355,1565.875 352.8346,1565.585 351.96875,1565.0312 C 351.1029,1564.4712 350.41557,1563.639 349.90625,1562.5312 C 349.40329,1561.4174 349.15625,1560.1276 349.15625,1558.625 C 349.15625,1557.0844 349.39692,1555.7513 349.90625,1554.6562 C 350.42194,1553.5615 351.09133,1552.7597 351.90625,1552.2188 C 352.72752,1551.6777 353.70414,1551.4062 354.84375,1551.4062 z M 333.5,1551.625 L 338.375,1551.625 C 339.62284,1551.6251 340.5277,1551.7454 341.0625,1552 C 341.59728,1552.2483 342.0312,1552.6886 342.375,1553.3125 C 342.71878,1553.93 342.90624,1554.6966 342.90625,1555.5625 C 342.90624,1556.6575 342.62217,1557.519 342.09375,1558.1875 C 341.57169,1558.8559 340.84271,1559.2969 339.875,1559.4688 C 340.37158,1559.8253 340.76904,1560.1984 341.09375,1560.625 C 341.41843,1561.0451 341.87723,1561.8113 342.4375,1562.9062 L 343.8125,1565.625 L 341.0625,1565.625 L 339.375,1562.5938 C 338.77018,1561.4924 338.37271,1560.805 338.15625,1560.5312 C 337.93978,1560.2512 337.71068,1560.0394 337.46875,1559.9375 C 337.22682,1559.8293 336.84728,1559.7813 336.3125,1559.7812 L 335.8125,1559.7812 L 335.8125,1565.625 L 333.5,1565.625 L 333.5,1551.625 z M 345,1551.625 L 347.3125,1551.625 L 347.3125,1565.625 L 345,1565.625 L 345,1551.625 z M 362.03125,1551.625 L 364.34375,1551.625 L 364.34375,1557.1562 L 368.90625,1557.1562 L 368.90625,1551.625 L 371.21875,1551.625 L 371.21875,1565.625 L 368.90625,1565.625 L 368.90625,1559.5 L 364.34375,1559.5 L 364.34375,1565.625 L 362.03125,1565.625 L 362.03125,1551.625 z M 372.78125,1551.625 L 381.90625,1551.625 L 381.90625,1554 L 378.5,1554 L 378.5,1565.625 L 376.1875,1565.625 L 376.1875,1554 L 372.78125,1554 L 372.78125,1551.625 z M 335.8125,1554 L 335.8125,1557.5625 L 337.53125,1557.5625 C 338.58172,1557.5625 339.24475,1557.4954 339.53125,1557.4062 C 339.81774,1557.3108 340.07173,1557.1238 340.25,1556.8438 C 340.42826,1556.5637 340.49999,1556.2147 340.5,1555.75 C 340.49999,1555.3043 340.42826,1554.9236 340.25,1554.6562 C 340.07173,1554.3825 339.80559,1554.1956 339.5,1554.0938 C 339.28353,1554.0238 338.66274,1554 337.625,1554 L 335.8125,1554 z"
id="path11301"
inkscape:connector-curvature="0" /></g><g
transform="matrix(0,0.99999999,-0.99999999,0,2291.2542,2047.0634)"
id="car-steering-down"><path
transform="matrix(0,1,1,0,-1157.8507,1015.8512)"
sodipodi:nodetypes="cccccccc"
inkscape:connector-curvature="0"
id="path11305"
d="M 530.37305,1424.5117 L 518.07691,1425.5117 L 540.78076,1398.5117 L 563.48462,1425.5117 L 551.18848,1424.5117 L 551.18848,1474.8734 L 530.37305,1474.8734 z"
style="color:#000000;fill:#1b421b;fill-opacity:1;fill-rule:nonzero;stroke:none;stroke-width:0.5;marker:none;visibility:visible;display:inline;overflow:visible;filter:url(#filter9921-4-2);enable-background:accumulate" /><path
style="color:#000000;fill:#1bb81b;fill-opacity:1;fill-rule:nonzero;stroke:#000000;stroke-width:0.5;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate"
d="M 266.65625,1535.9062 L 239.65625,1558.625 L 266.65625,1581.3438 L 265.65625,1569.0312 L 316.03125,1569.0312 L 316.03125,1548.2188 L 265.65625,1548.2188 L 266.65625,1535.9062 z M 283.3125,1551.625 L 291.84375,1551.625 L 291.84375,1554 L 285.625,1554 L 285.625,1557.0938 L 291.40625,1557.0938 L 291.40625,1559.4688 L 285.625,1559.4688 L 285.625,1563.2812 L 292.03125,1563.2812 L 292.03125,1565.625 L 283.3125,1565.625 L 283.3125,1551.625 z M 294.03125,1551.625 L 301.875,1551.625 L 301.875,1554 L 296.34375,1554 L 296.34375,1557.3125 L 301.125,1557.3125 L 301.125,1559.6875 L 296.34375,1559.6875 L 296.34375,1565.625 L 294.03125,1565.625 L 294.03125,1551.625 z M 303,1551.625 L 312.125,1551.625 L 312.125,1554 L 308.71875,1554 L 308.71875,1565.625 L 306.40625,1565.625 L 306.40625,1554 L 303,1554 L 303,1551.625 z M 273.5625,1551.75 L 275.875,1551.75 L 275.875,1563.2812 L 281.625,1563.2812 L 281.625,1565.625 L 273.5625,1565.625 L 273.5625,1551.75 z"
id="path11307"
inkscape:connector-curvature="0" /></g></g></g><g
inkscape:groupmode="layer"
id="layer4"
inkscape:label="tank"

Before

Width:  |  Height:  |  Size: 431 KiB

After

Width:  |  Height:  |  Size: 448 KiB

View File

@ -1927,7 +1927,7 @@ void VehicleConfigurationHelper::setupDualAileron()
channels[3].throttle2 = 0;
channels[3].roll = 0;
channels[3].pitch = 0;
channels[3].yaw = 100;
channels[3].yaw = -100;
guiSettings.fixedwing.FixedWingThrottle = 3;
guiSettings.fixedwing.FixedWingRoll1 = 1;
@ -1979,7 +1979,7 @@ void VehicleConfigurationHelper::setupAileron()
channels[3].throttle2 = 0;
channels[3].roll = 0;
channels[3].pitch = 0;
channels[3].yaw = 100;
channels[3].yaw = -100;
guiSettings.fixedwing.FixedWingThrottle = 3;
guiSettings.fixedwing.FixedWingRoll1 = 1;
@ -2030,7 +2030,7 @@ void VehicleConfigurationHelper::setupVtail()
channels[1].throttle2 = 0;
channels[1].roll = 0;
channels[1].pitch = 100;
channels[1].yaw = 100;
channels[1].yaw = -100;
// Left Vtail Servo (Chan 4)
channels[3].type = MIXER_TYPE_SERVO;
@ -2038,7 +2038,7 @@ void VehicleConfigurationHelper::setupVtail()
channels[3].throttle2 = 0;
channels[3].roll = 0;
channels[3].pitch = -100;
channels[3].yaw = 100;
channels[3].yaw = -100;
guiSettings.fixedwing.FixedWingThrottle = 3;
guiSettings.fixedwing.FixedWingRoll1 = 1;

View File

@ -0,0 +1,17 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>System Configuration : BadThrottleOrCollectiveInputRange</h1>
<p>
There is a problem with throttle/collective channel configuration :
<ul>
<li>Redo your input calibration.</li>
<li>The range for the channel between min and max must be more than 300us.</li>
</ul>
</p>
</body>
</html>

View File

@ -0,0 +1,17 @@
<html>
<head>
<title></title>
<meta content="">
<style></style>
</head>
<body>
<h1>Configuration Système : BadThrottleOrCollectiveInputRange</h1>
<p>
Il y a un problème avec la configuration du canal throttle/collective :
<ul>
<li>Relancez la calibration des entrées.</li>
<li>La différence entre la valeur mini et maxi doit faire au moins 300µs.</li>
</ul>
</p>
</body>
</html>

View File

@ -33,6 +33,7 @@
<file>html/Stabilization-Critical.html</file>
<file>html/SystemConfiguration-UnsupportedConfig_OneShot.html</file>
<file>html/SystemConfiguration-FlightMode.html</file>
<file>html/SystemConfiguration-BadThrottleOrCollectiveInputRange.html</file>
<file>html/BootFault-RebootRequired.html</file>
</qresource>
<qresource prefix="/systemhealth" lang="fr">
@ -69,6 +70,7 @@
<file alias="html/Stabilization-Critical.html">html/fr/Stabilization-Critical.html</file>
<file alias="html/SystemConfiguration-UnsupportedConfig_OneShot.html">html/fr/SystemConfiguration-UnsupportedConfig_OneShot.html</file>
<file alias="html/SystemConfiguration-FlightMode.html">html/fr/SystemConfiguration-FlightMode.html</file>
<file alias="html/SystemConfiguration-BadThrottleOrCollectiveInputRange.html">html/fr/SystemConfiguration-BadThrottleOrCollectiveInputRange.html</file>
<file alias="html/BootFault-RebootRequired.html">html/fr/BootFault-RebootRequired.html</file>
</qresource>

View File

@ -72,7 +72,7 @@ MSG_FLASH_IMG = $(QUOTE) FLASH_IMG $(MSG_EXTRA) $(QUOTE)
toprel = $(subst $(realpath $(ROOT_DIR))/,,$(abspath $(1)))
# Function to replace special characters like is done for the symbols.
replace_special_chars = $(subst ~,_,$(subst @,_,$(subst :,_,$(subst -,_,$(subst .,_,$(subst /,_,$1))))))
replace_special_chars = $(subst +,_,$(subst ~,_,$(subst @,_,$(subst :,_,$(subst -,_,$(subst .,_,$(subst /,_,$1)))))))
# Display compiler version information.
.PHONY: gccversion

View File

@ -228,7 +228,8 @@ class Repo:
json_data['last_tag'] = self._last_tag
json_data['num_commits_past_tag'] = self._num_commits_past_tag
json_data['branch'] = self._branch
json_data['dirty'] = self._dirty
# version-info.json is for use with git archive which doesn't take in dirty changes
json_data['dirty'] = False
json_path = os.path.join(path, 'version-info.json')
with open(json_path, 'w') as json_file:

View File

@ -6,26 +6,72 @@ ifndef OPENPILOT_IS_COOL
$(error Top level Makefile must be used to build this target)
endif
DEB_VER := $(subst RELEASE-,,$(PACKAGE_LBL))-1
DEB_DIR := $(ROOT_DIR)/package/linux/debian
DEB_BUILD_DIR := $(ROOT_DIR)/debian
# Are we using a debian based distro?
ifneq ($(shell which dpkg 2> /dev/null),)
SED_DATE_STRG = $(shell date -R)
SED_SCRIPT = s/<VERSION>/$(DEB_VER)/;s/<DATE>/$(SED_DATE_STRG)/
DEB_DIST := unstable
# Instead of RELEASE-15.01-RC1 debian wants 15.01~RC1
UPSTREAM_VER := $(subst -,~,$(subst RELEASE-,,$(PACKAGE_LBL)))
DEB_REV := 1
ifeq ($(DEB_DIST), trusty)
DEB_REV := $(DEB_REV)$(DEB_DIST)1
endif
DEB_NAME := openpilot
DEB_ORIG_SRC := $(PACKAGE_DIR)/$(DEB_NAME)_$(UPSTREAM_VER).orig.tar.gz
DEB_PACKAGE_DIR := $(PACKAGE_DIR)/$(DEB_NAME)-$(UPSTREAM_VER)
DEB_ARCH := $(shell dpkg --print-architecture)
DEB_PACKAGE_NAME := $(DEB_NAME)_$(UPSTREAM_VER)-$(DEB_REV)_$(DEB_ARCH)
DEB_DIR := package/linux/debian
DEB_ARCH := $(shell dpkg --print-architecture)
DEB_PACKAGE_NAME := openpilot_$(DEB_VER)_$(DEB_ARCH)
SED_DATE_STRG = $(shell date -R)
SED_SCRIPT = s/<VERSION>/$(UPSTREAM_VER)-$(DEB_REV)/;s/<DATE>/$(SED_DATE_STRG)/;s/<DIST>/$(DEB_DIST)/
# Ubuntu 14.04 (Trusty Tahr) has different names for the qml-modules
TRUSTY_DEPS_SED := s/qml-module-qtquick-controls/qtdeclarative5-controls-plugin/g; \
s/qml-module-qtquick-dialogs/qtdeclarative5-dialogs-plugin/g; \
s/qml-module-qtquick-localstorage/qtdeclarative5-localstorage-plugin/g; \
s/qml-module-qtquick-particles2/qtdeclarative5-particles-plugin/g; \
s/qml-module-qtquick2/qtdeclarative5-qtquick2-plugin/g; \
s/qml-module-qtquick-window2/qtdeclarative5-window-plugin/g; \
s/qml-module-qtquick-xmllistmodel/qtdeclarative5-xmllistmodel-plugin/g;
# Leave off Qt and ARM compiler dependencies if calling package target under the assumption that
# OP is providing them or the user already has them installed because OP is already built.
PACKAGE_DEPS_SED := s/python.*/python/;s/{misc:Depends}.*/{misc:Depends}/;
.PHONY: package
package:
$(V1) echo "Building Linux package, please wait..."
$(V1) cp -rL $(DEB_DIR) $(DEB_BUILD_DIR)
$(V1) sed -i -e "$(SED_SCRIPT)" $(DEB_BUILD_DIR)/changelog
package: debian
@$(ECHO) "Building Linux package, please wait..."
# Override clean and build because OP has already performed them.
$(V1) printf "override_dh_auto_clean:\noverride_dh_auto_build:\n\t#\n" >> debian/rules
$(V1) sed -i -e "$(PACKAGE_DEPS_SED)" debian/control
$(V1) dpkg-buildpackage -b -us -uc
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).deb $(BUILD_DIR)/$(DEB_PACKAGE_NAME).deb
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(BUILD_DIR)/$(DEB_PACKAGE_NAME).changes
$(V1) rm -rf $(DEB_BUILD_DIR)
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).deb $(PACKAGE_DIR)
$(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(PACKAGE_DIR)
$(V1) rm -r debian
.PHONY: debian
debian: $(DEB_DIR)
$(V1) rm -rf debian
$(V1) cp -rL $(DEB_DIR) debian
$(V1) sed -i -e "$(SED_SCRIPT)" debian/changelog
ifeq ($(DEB_DIST), trusty)
$(V1) sed -i -e "$(TRUSTY_DEPS_SED)" debian/control
endif
.PHONY: package_src
package_src: $(DEB_ORIG_SRC_NAME) $(DEB_PACKAGE_DIR)
$(V1) cd $(DEB_PACKAGE_DIR) && dpkg-buildpackage -S -us -uc
$(DEB_ORIG_SRC): $(DIST_NAME).gz | $(PACKAGE_DIR)
$(V1) cp $(DIST_NAME).gz $(DEB_ORIG_SRC)
$(DEB_PACKAGE_DIR): $(DEB_ORIG_SRC) debian | $(PACKAGE_DIR)
$(V1) tar -xf $(DEB_ORIG_SRC) -C $(PACKAGE_DIR)
$(V1) mv debian $(PACKAGE_DIR)/$(PACKAGE_NAME)
$(V1) rm -rf $(DEB_PACKAGE_DIR) && mv $(PACKAGE_DIR)/$(PACKAGE_NAME) $(DEB_PACKAGE_DIR)
endif # Debian based distro?
##############################
#
# Install OpenPilot

View File

@ -1,4 +1,4 @@
openpilot (<VERSION>) unstable; urgency=low
openpilot (<VERSION>) <DIST>; urgency=low
* Release from upstream Git (testing - unstable)

View File

@ -1,15 +1,15 @@
Source: openpilot
Section: unknown
Section: electronics
Priority: optional
Maintainer: James Duley <james@openpilot.org>
Build-Depends: debhelper (>= 8.0.0)
Standards-Version: 3.9.4
Build-Depends: debhelper (>= 9), libudev-dev, libusb-1.0-0-dev, libsdl1.2-dev, python, gcc-arm-none-eabi (>=4.9), qt5-default, qttools5-dev-tools, libqt5svg5-dev, qtdeclarative5-dev, qml-module-qtquick-controls, libqt5serialport5-dev, qtmultimedia5-dev, qtscript5-dev, libqt5opengl5-dev
Standards-Version: 3.9.5
Homepage: http://www.openpilot.org
Vcs-Git: git://git.openpilot.org/OpenPilot.git
Vcs-Browser: http://git.openpilot.org/changelog/OpenPilot
Package: openpilot
Architecture: any
Depends: ${shlibs:Depends}, ${misc:Depends}
Depends: ${shlibs:Depends}, ${misc:Depends}, qml-module-qtquick-controls, qml-module-qtquick-dialogs, qml-module-qtquick-xmllistmodel, qml-module-qtquick-localstorage, qml-module-qtquick-particles2, qml-module-qtquick-window2, qml-module-qtquick2
Description: OpenPilot GCS
OpenPilot Ground Control Station software

9
package/linux/debian/rules Normal file → Executable file
View File

@ -11,15 +11,8 @@ export DH_OPTIONS
%:
dh $@
# Disabled because OpenPilot makefile cleans and builds.
override_dh_auto_clean:
#
override_dh_auto_build:
#dh_auto_build -- all
override_dh_auto_test:
# Fails non-silently because it is run under fakeroot.
dh_auto_build -- all
override_dh_auto_install:
dh_auto_install -- prefix=/usr

View File

@ -0,0 +1 @@
3.0 (quilt)

View File

@ -36,6 +36,7 @@
<option>RebootRequired</option>
<option>FlightMode</option>
<option>UnsupportedConfig_OneShot</option>
<option>BadThrottleOrCollectiveInputRange</option>
</options>
</field>
<field name="ExtendedAlarmSubStatus" units="" type="uint8" defaultvalue="0">