[[searchwing-ardupilot-parameters]]

Differences

This shows you the differences between two versions of the page.

Link to this comparison view

Both sides previous revision Previous revision
Next revision
Previous revision
Last revision Both sides next revision
searchwing-ardupilot-parameters [2020/02/27 10:49]
beckmanf [Servo settings] adapted to KURDI
searchwing-ardupilot-parameters [2022/05/23 14:29]
wf68spef [Ardupilot Parameter Setup]
Line 1: Line 1:
 ====== Ardupilot Parameter Setup ====== ====== Ardupilot Parameter Setup ======
  
-[[https://​ardupilot.org/​plane/​docs/​parameters-Plane-stable-V4.0.3.html|Description ​of the parameters]]+[[https://​ardupilot.org/​plane/​docs/​parameters-Plane-stable-V4.2.0.html|Ardupilot description ​of the parameters]] 
 + 
 +[[https://​gitlab.com/​searchwing/​operational/​searchwing-config/​-/​blob/​master/​ardupilot/​searchwing/​LATEST.params|Standard set of SearchWing ArduPilot ​parameters]]
  
 ==== Arming / Safety ==== ==== Arming / Safety ====
Line 8: Line 10:
 |BRD_SAFETYENABLE ​  ​|0 ​          ​|Disable the safety switch ​  ​|Safety switch is not accessible, because it is inside the fuselage | |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 | |ARMING_RUDDER ​     |2           |Arm and Disarm with rudder ​ |Default is that you can only arm but not disarm with rudder |
-|BRD_SAFETY_MASK ​   |15          ​|Servo 1,2,3,4 enabled ​      ​|These servos can move also in safe state - NOT REQUIRED??? |+|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| |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)| |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? Is the safety_mask maybe not required because the pixracer is always in safe state? Safe and disarmed is different?
  
Line 39: Line 42:
  
 ^Parametername ​     ^Value ​      ​^Description ​                ​^Remark ​ ^ ^Parametername ​     ^Value ​      ​^Description ​                ​^Remark ​ ^
-|MIXING_GAIN ​       |1.        ​|Mixing of pitch and rudder to vtail |Default is 0.5 - full pitch will yield only 50 percent of vtail servo output |+|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 |
  
  
Line 57: Line 60:
 ^Parametername ​     ^Value ​      ​^Description ​                ​^Remark ​ ^ ^Parametername ​     ^Value ​      ​^Description ​                ​^Remark ​ ^
 |SERIAL2_BAUD ​      ​|9 ​          |9600 Baud |reduced to 9600 as otherwise no wifi with MAVESP connection possible | |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 |+|SERIAL2_PROTOCOL ​  |2           ​|MAVLink2 | Mavlink2 needed for PLAY_TUNE | 
 +|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 ​      ​|5 ​          |5 Hz | Contains GLOBAL_POSITION_INT,​ LOCAL_POSITION_NED messages | 
 +|SR2_EXTRA1 ​      ​|5 ​          |5 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:​ [[https://​ardupilot.org/​plane/​docs/​parameters.html#​log-bitmask-log-bitmask|Log Bitmask Description]] 
 + 
 +Enabled all (''​==65535''​) results in following per message data sum in bytes for a 20 minute flight: 
 + 
 +{{ ::​average_log_msg_sizes.png?​1400 |}} 
 + 
 +  * 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 [[https://​github.com/​ArduPilot/​ardupilot/​blob/​6af0f460afa6f51c41056cd25fe2c70164d9d460/​ArduPlane/​Log.cpp#​L39|Code]]). For the attitude two settings are available: Fast (50Hz), Medium(10Hz) according to [[https://​github.com/​ArduPilot/​ardupilot_wiki/​blob/​6c81c28126e6cb2bdbb9cb58291342ca3ade96a0/​dev/​source/​docs/​using-the-command-line-interpreter-to-configure-apmcopter.rst#​reading-logs-through-the-cli|LINK]]. I think 10Hz could be enough for us. __**But in the Code actually the Logging is done with 25Hz**__ (see [[https://​github.com/​ArduPilot/​ardupilot/​blob/​d8d3494b170d50f7b45dced928cd5d9150b50d2f/​ArduPlane/​ArduPlane.cpp#​L87|Code]]) 
 +  * IMU logging **could be disabled,** as its already triggerd by attitude logging anyway (see [[https://​github.com/​ArduPilot/​ardupilot/​blob/​d8d3494b170d50f7b45dced928cd5d9150b50d2f/​ArduPlane/​ArduPlane.cpp#​L209|Code]]),​ but with less data amount. **UPDATE:** Actually IMU also loggs the **BARO**, so it should not be disabled (see [[https://​github.com/​ArduPilot/​ardupilot/​search?​q=set_log_baro_bit|INFO]]. 
 +  * TECS (Total Energy Control System) controls altitude vs speed and is important and **should be enabled**. 
 +  * CTUN Logs contain baro and ** should be enabled.** 
 +  * NTUN Logs navigation tuning info at 10 Hz and ** should ​ be enabled.** 
 + 
 +This results in the following Table (according to [[https://​ardupilot.org/​plane/​docs/​parameters.html#​log-bitmask-log-bitmask|Log Bitmask Description]]):​ 
 + 
 +^ Bit ^ Meaning ​   ^ Enabled ^ 
 +| 0 | ATTITUDE_FAST(50Hz) | OFF | 
 +| 1 | ATTITUDE_MED(10Hz) | ON | 
 +| 2 | GPS | ON | 
 +| 3 | PM | ON | 
 +| 4 | CTUN | ON | 
 +| 5 | NTUN | ON | 
 +| 6 | MODE | ON | 
 +| 7 | IMU | ON | 
 +| 8 | CMD | ON | 
 +| 9 | CURRENT | ON | 
 +| 10 | COMPASS | ON | 
 +| 11 | TECS | ON | 
 +| 12 | CAMERA | OFF | 
 +| 13 | RC | ON | 
 +| 14 | SONAR | OFF | 
 +| 15 | ARM/DISARM | ON | 
 +| 19 | IMU_RAW | OFF | 
 +| 20 | ATTITUDE_FULLRATE | OFF | 
 + 
 +This results into the following parameter values. In the remarks you can see empirical Results for some settings from ArduPlane Simulator. 
 + 
 +^Parametername ​     ^Value ​      ​^Description ​                ​^Remark ​ ^ 
 +|LOG_BITMASK ​      ​| ​ 65535          | Log all    |     ~3.04 MB/Min Log          | 
 +|LOG_BITMASK ​      ​| ​ 45054          | Log from table above (IMU disabled) |     ​TODO ​      | 
 +|LOG_BITMASK ​      ​| ​ TODO          | Log from table above (IMU enabled) |     ​TODO ​       | 
 +|LOG_BITMASK ​      ​| ​ 2              | Log only attitude Medium |     ~1.75 MB/Min Log         | 
  
 ===== MAVESP8266 Wifi Telemetry ===== ===== MAVESP8266 Wifi Telemetry =====
Line 68: Line 128:
  
  
-    1 1 BATT_AMP_PERVLT 36.000000000000000000 9+    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_CURR_PIN 3 2
     1 1 BATT_MONITOR 4 2     1 1 BATT_MONITOR 4 2
     1 1 BATT_SERIAL_NUM -1 6     1 1 BATT_SERIAL_NUM -1 6
-    1 1 BATT_VOLT_MULT 10.207025527954101563 9+    1 1 BATT_VOLT_MULT 10.213 9
     1 1 BATT_VOLT_PIN 2 2     1 1 BATT_VOLT_PIN 2 2
     1 1 BATT_WATT_MAX 0 4     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:
 +
 +https://​www.hobbywingdirect.com/​products/​rpm-sensor
 +
 +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:
 +
 +https://​ardupilot.org/​copter/​docs/​common-rpm.html
 +
 +
 +^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 https://​www.radiocontrolinfo.com/​brushless-motor-efficiency/​measuring-motor-rpm/​ :
 +
 +''​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 ===== ===== Tuning =====
Line 95: Line 195:
 If min groundspeed is net met, plane increases throttle If min groundspeed is net met, plane increases throttle
  
-    1 1 NAVL1_DAMPING 0.600000023841857910 9  +    1 1 NAVL1_DAMPING 0.800000023841857910 9  
-    1 1 NAVL1_PERIOD 10.000000000000000000 9+    1 1 NAVL1_PERIOD 17.000000000000000000 9
  
-TBD!+This is the default value for NAVL1 (Beck, 27.2.20)
  
     1 1 PTCH2SRV_RLL 1.299999952316284180 9     1 1 PTCH2SRV_RLL 1.299999952316284180 9
Line 106: Line 206:
     1 1 TECS_CLMB_MAX 6.500000000000000000 9     1 1 TECS_CLMB_MAX 6.500000000000000000 9
     1 1 TECS_SINK_MAX 5.000000000000000000 9     1 1 TECS_SINK_MAX 5.000000000000000000 9
-    1 1 TECS_SPDWEIGHT 1.000000000000000000 9 #TBD! 
- 
-Height is more important than speed 
  
-SPDWEIGHT - Setting it to 0.0 will cause the pitch control to control height and ignore speed errors. This will normally improve height accuracy but give larger airspeed errors. 
  
-    1 1 WP_LOITER_RAD 40 4  +    1 1 WP_LOITER_RAD 60 4  
-    1 1 WP_RADIUS 25 4+    1 1 WP_RADIUS 90 4
  
-TBD; should increase precission+WP settings are set to default (Beck, 27.2.20)
  
 # Modes Setup (Special Switches) # Modes Setup (Special Switches)
  
 to be done. to be done.
  • searchwing-ardupilot-parameters.txt
  • Last modified: 2022/05/23 14:30
  • by wf68spef