This is an old revision of the document!
Ardupilot Parameter Setup
Arming / Safety
Parametername | Value | Description | Remark |
---|---|---|---|
BRD_SAFETYENABLE | 0 | Disable the safety switch | Safety switch is not accessible, because it is inside the fuselage |
ARMING_RUDDER | 2 | Arm and Disarm with rudder | Default is that you can only arm but not disarm with rudder |
BRD_SAFETY_MASK | 27 | Servo 1,2,4,5 enabled | These servos can move also in safe state - NOT REQUIRED??? |
INS_GYRO_CAL | 0 | Disable Gyro Calibration at startup | This prevents INS calibration at startup |
ARSPD_TYPE | 0 | No Airspeed Pitot Tube | Disable the Pitottube airspeed sensor (we don't have one) |
COMPASS_USE2 | 0 | Disable PixRacer compass | Disable the PixRacer internal compass |
COMPASS_USE3 | 0 | Disable PixRacer compass | Disable the PixRacer internal compass |
Is the safety_mask maybe not required because the pixracer is always in safe state? Safe and disarmed is different?
Servo settings
Parametername | Value | Description | Remark |
---|---|---|---|
SERVO1_FUNCTION | 4 | Aileron left | |
SERVO1_REVERSED | 1 | Reverse the servo | |
SERVO2_FUNCTION | 79 | VTAIL left | |
SERVO2_REVERSED | 0 | Normal | |
SERVO3_FUNCTION | 70 | Throttle | |
SERVO3_REVERSED | 0 | Reverse the servo | |
SERVO4_FUNCTION | 80 | VTAIL right | |
SERVO4_REVERSED | 1 | Reverse servo | |
SERVO5_FUNCTION | 4 | Aileron right | |
SERVO5_REVERSED | 1 | Reversed | |
Servo ranges for servo 1,2,4,5 (aileron and vtail) | |||
SERVOx_MIN | 1000 | Minimum servo value | Default is 1100 - too high |
SERVOx_MAX | 2000 | Maximum servo value | Default is 1900 - too low |
SERVOx_TRIM | 1500 | Default value | Leitwerk mitte |
Servo ranges for throttle | |||
SERVO3_MIN | 900 | Minimum servo value | CHECK THIS!!! Maybe 950 to be able to arm |
SERVO3_MAX | 2000 | Maximum servo value | Default is 1900 - too low |
SERVO3_TRIM | 900 | Default value | zero throttle |
Servo/PID Controller
Parametername | Value | Description | Remark |
---|---|---|---|
MIXING_GAIN | 0.75 | Mixing of pitch and rudder to vtail | Default is 0.5 - full pitch will yield only 50 percent of vtail servo output |
FrSky Telemetrie
Parametername | Value | Description | Remark |
---|---|---|---|
SERIAL4_BAUD | 57 | 57600 Baud | |
SERIAL4_PROTOCOL | 10 | FrSky SPort Passthrough (OpenTX) | Format for the FrSyk Telemetry |
Aktiviert die FrSky Telemetrie auf dem FrSky Port des Pixracers
PI Zero Telemetry for image metadata
Metadata consist of GPS / Timestamp
Parametername | Value | Description | Remark |
---|---|---|---|
SERIAL2_BAUD | 9 | 9600 Baud | reduced to 9600 as otherwise no wifi with MAVESP connection possible |
SERIAL2_PROTOCOL | 1 | MAVLink1 | Only MAVLink1 works for pymavlink on pi |
SR2_RAW_SENS | 0 | 0 Hz | no raw data needed |
SR2_EXT_STAT | 1 | 1 Hz | |
SR2_RC_CHAN | 0 | 0 Hz | |
SR2_RAW_CTRL | 0 | 0 Hz | |
SR2_POSITION | 2 | 2 Hz | Contains GLOBAL_POSITION_INT, LOCAL_POSITION_NED messages |
SR2_EXTRA1 | 2 | 2 Hz | Contains ATTITUDE message |
SR2_EXTRA2 | 0 | 0 Hz | |
SR2_EXTRA3 | 1 | 1 Hz | Contains SYSTEM_TIME message |
SR2_PARAMS | 0 | 0 Hz | |
SR2_ADSB | 0 | 0 Hz |
Logging
Several bits can be set for logging of different informations:
Enabled all (==65535
) results in following per message data sum in bytes for a 20 minute flight:
- The PID, NKF(EKF) and IMU take a lot of space.
- The PID and EKF is saved using the “attitude” bit in the logging parameter setting (see ). For the attitude two settings are available: Fast (50Hz), Medium(10Hz) according to . I think 10Hz could be enough for us.
- IMU logging could be disabled, as its already triggerd by attitude logging anyway (see ), but with less data amount.
- TECS (Total Energy Control System) is not analyzed so far and could be disabled.
- CTUN Logs control loop tuning info at 10 Hz. This information is useful for tuning servo control loop gain values. AFAIK this is not analyzed so far and could be disabled.
- NTUN Logs navigation tuning info at 10 Hz. This information is useful for tuning navigation control loop gain values. AFAIK this is not analyzed so far and could be disabled.
This results in the following Table (according to ):
Bit | Meaning | Enabled |
---|---|---|
0 | ATTITUDE_FAST | OFF |
1 | ATTITUDE_MED | ON |
2 | GPS | ON |
3 | PM | ON |
4 | CTUN | OFF |
5 | NTUN | OFF |
6 | MODE | ON |
7 | IMU | OFF |
8 | CMD | ON |
9 | CURRENT | ON |
10 | COMPASS | ON |
11 | TECS | OFF |
12 | CAMERA | OFF |
13 | RC | ON |
14 | SONAR | OFF |
15 | ARM/DISARM | ON |
19 | IMU_RAW | OFF |
This results into the following parameter value
Parametername | Value | Description | Remark |
---|---|---|---|
LOG_BITMASK | 42830 | See table above |
This is untested, but i guess it should reduce the dataflash size at least by 2/3.
MAVESP8266 Wifi Telemetry
Parametername | Value | Description | Remark |
---|---|---|---|
SERIAL5_BAUD | 921 | 921600 Baud | |
SERIAL5_PROTOCOL | 2 | MAVLink2 |
Power Module
1 1 BATT_AMP_PERVLT 24.0 9 1 1 BATT_AMP_OFFSET -0.07 9 1 1 BATT_CURR_PIN 3 2 1 1 BATT_MONITOR 4 2 1 1 BATT_SERIAL_NUM -1 6 1 1 BATT_VOLT_MULT 10.213 9 1 1 BATT_VOLT_PIN 2 2 1 1 BATT_WATT_MAX 0 4
RPM
To measure the RPM of the motor we can use a BACK-EMF Measurement from 2 of the 3 motorcables. For more info check out the page:
We connected the output pins to a AUX pin of the FC. Check out the info from Ardupilot for some info regarding the following config:
Parametername | Value | Description | Remark |
---|---|---|---|
RPM_MAX | 100000.000000000000000000 | ||
RPM_MIN | 10.000000000000000000 | ||
RPM_MIN_QUAL | 0.100000001490116119 | ||
RPM_PIN | Pin | PIN | depending on FC |
RPM_SCALING | 0.143 | check the hints below for this setting | |
RPM_TYPE | 2 | AUX | Type needs to be AUX to calc using the given sensor |
The RPM in general can be calculated using the formula from :
RPM = ( 120 x Frequency ) / # of Motor Poles
Thats because:
The AC current that is produced alternates each time 2 magnetic poles pass by a winding in the stator.
As Ardupilot measures the periode duration dt_avg
of the sensor rectangular signal, and calculates the RPM using
float rpm = scaling * (1.0e6 / dt_avg) * 60;
the scaling needs to correct this using
SCALING = ( 1 / # of Motor Poles ) * 2
For the Extron 800KV Motor , we have 14 Poles.
Tuning
(David, Mülli, Simon)
1 1 ARSPD_FBW_MAX 28 4 1 1 ARSPD_FBW_MIN 12 4
Min and max airspeed - default 22 / 9
1 1 LIM_PITCH_MAX 3000 4 1 1 LIM_PITCH_MIN -2000 4
default 2000, -2500
1 1 MIN_GNDSPD_CM 800 6
If min groundspeed is net met, plane increases throttle
1 1 NAVL1_DAMPING 0.800000023841857910 9 1 1 NAVL1_PERIOD 17.000000000000000000 9
This is the default value for NAVL1 (Beck, 27.2.20)
1 1 PTCH2SRV_RLL 1.299999952316284180 9
This parameter controls how much elevator to add in turns to keep the nose level. Many aircraft require a small change to this parameter from the default of 1.0. (autotune)
1 1 TECS_CLMB_MAX 6.500000000000000000 9 1 1 TECS_SINK_MAX 5.000000000000000000 9
1 1 WP_LOITER_RAD 60 4 1 1 WP_RADIUS 90 4
WP settings are set to default (Beck, 27.2.20)
# Modes Setup (Special Switches)
to be done.