Skip to content

Commit

Permalink
IMPROVEMENT: Update 4.3.8 and 4.4.4 templates with new components
Browse files Browse the repository at this point in the history
  • Loading branch information
amilcarlucas committed May 13, 2024
1 parent 360baa0 commit 127f29c
Show file tree
Hide file tree
Showing 59 changed files with 792 additions and 2,918 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
# Bitmask: 0:IMU1,1:IMU2,2:IMU3
# RebootRequired: True
# Default: 0
INS_LOG_BAT_MASK,3 # the Matek H743 fligth controller only has two IMUs
INS_LOG_BAT_MASK,3 # the Matek H743 fligth controller only has two IMUs

# Enable temperature calibration
# Enable the use of temperature calibration parameters for this IMU. For automatic learning set to 2 and
Expand All @@ -13,7 +13,7 @@ INS_LOG_BAT_MASK,3 # the Matek H743 fligth controller only has two IMUs
# 1: Enabled
# 2: LearnCalibration
# Default: 0
INS_TCAL1_ENABLE,2 # Activates the temperature calibration for IMU 1 at the next start
INS_TCAL1_ENABLE,2 # Activates the temperature calibration for IMU 1 at the next start

# Temperature calibration max
# The maximum temperature that the calibration is valid for. This must be at least 10 degrees above TMIN
Expand All @@ -22,7 +22,7 @@ INS_TCAL1_ENABLE,2 # Activates the temperature calibration for IMU 1 at the next
# Units: degC (degrees Celsius)
# Calibration: 1
# Default: 70
INS_TCAL1_TMAX,60 # our H7 processor acts as a heater and heats up the board to almost 60 deg
INS_TCAL1_TMAX,60 # our H7 processor acts as a heater and heats up the board to almost 60 deg

# Enable temperature calibration
# Enable the use of temperature calibration parameters for this IMU. For automatic learning set to 2 and
Expand All @@ -32,7 +32,7 @@ INS_TCAL1_TMAX,60 # our H7 processor acts as a heater and heats up the board to
# 1: Enabled
# 2: LearnCalibration
# Default: 0
INS_TCAL2_ENABLE,2 # Activates the temperature calibration for IMU 2 at the next start
INS_TCAL2_ENABLE,2 # Activates the temperature calibration for IMU 2 at the next start

# Temperature calibration max
# The maximum temperature that the calibration is valid for. This must be at least 10 degrees above TMIN
Expand All @@ -41,19 +41,19 @@ INS_TCAL2_ENABLE,2 # Activates the temperature calibration for IMU 2 at the next
# Units: degC (degrees Celsius)
# Calibration: 1
# Default: 70
INS_TCAL2_TMAX,60 # our H7 processor acts as a heater and heats up the board to almost 60 deg
INS_TCAL2_TMAX,60 # our H7 processor acts as a heater and heats up the board to almost 60 deg

# Log bitmask
# Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types
# you want to be saved. It is usually best just to enable all basiclog types by setting this to 65535.
# Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,5:Navigation Tuning,6:RC input,7:IMU,8:Mission Commands,9:Battery Monitor,10:RC output,11:Optical Flow,12:PID,13:Compass,15:Camera,17:Motors,18:Fast IMU,19:Raw IMU,20:Video Stabilization,21:Fast harmonic notch logging
# Default: 176126
LOG_BITMASK,524416 # Only for IMU and Raw-IMU
LOG_BITMASK,524416 # Only for IMU and Raw-IMU

# Enable logging while disarmed
# If LOG_DISARMED is set to 1 then logging will be enabled while disarmed. This can make for very large
# logfiles but can help a lot when tracking down startup issues
# 0: Disabled
# 1: Enabled
# Default: 0
LOG_DISARMED,1 # to gather data for the offline IMU temperature compensation while the FC is disarmed
LOG_DISARMED,1 # Gather data for the offline IMU temperature compensation while the FC is disarmed
Original file line number Diff line number Diff line change
Expand Up @@ -274,21 +274,6 @@ RC9_OPTION,300 # Used to jump to the next waypoint
# Default: 0
RSSI_TYPE,3 # TBS Crossfire protocol provides RSSI

# Telemetry 2 Baud Rate
# The baud rate of the Telem2 port. Most stm32-based boards can support rates of up to 1500. If you setup a
# rate you cannot support and then can't connect to your board you should load a firmware from a different
# vehicle type. That will reset all your parameters to defaults.
# 1: 1200 115: 115200
# 2: 2400 230: 230400
# 4: 4800 256: 256000
# 9: 9600 460: 460800
# 19: 19200 500: 500000
# 38: 38400 921: 921600
# 57: 57600 1500: 1500000
# 111: 111100
# Default: 57
SERIAL2_BAUD,115 # For Mavlink over crossfire

# Serial7 protocol selection
# Control what protocol Serial7 port should be used for. Note that the Frsky options require external
# converter hardware. See the wiki for details.
Expand Down
Loading

0 comments on commit 127f29c

Please sign in to comment.