Skip to content

Commit

Permalink
Asgard: add default vehicle params
Browse files Browse the repository at this point in the history
  • Loading branch information
hendjoshsr71 committed Jul 16, 2024
1 parent 07493ed commit 216b07c
Show file tree
Hide file tree
Showing 26 changed files with 1,927 additions and 0 deletions.
Binary file added Tools/bootloaders/Asgard_QAVR2_bl.bin
Binary file not shown.
1,211 changes: 1,211 additions & 0 deletions Tools/bootloaders/Asgard_QAVR2_bl.hex

Large diffs are not rendered by default.

454 changes: 454 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Asgard_QAVR2/defaults.parm

Large diffs are not rendered by default.

1 change: 1 addition & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Asgard_QAVR2/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
include ../MatekH743/hwdef-bl.dat
4 changes: 4 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Asgard_QAVR2/hwdef.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Asgard QAVR2

# Flight Controller
include ../MatekH743-bdshot/hwdef.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
# BLHeli & AM32 Base Parameters for all applicable ESCs

# Defaults for DShot ESCs
# MOT_PWM_MAX 2000
# MOT_PWM_MIN 1000

# Allow for BLHeli32, ESC-Configurator.com pass through support
SERVO_BLH_AUTO 1

# This assumes a sane motor ordering of using the first four servo outputs for the motors
# Not ture for QUAD planes
# This needs to be un-defined and redfined on quad planes
SERVO_BLH_BDMASK 15
SERVO_BLH_MASK 15

# Sets output port to be the first USB port, should default to mavlink
# Defaults to the first USB port
# SERVO_BLH_PORT 0

# SET DShot ESC type
# 1 : BLHeli32 Normal
# 3 : BLHeli32 + Extended Telemetry
# The ESC must support extended telemetry IE BLHeli 32.10 or greater
SERVO_DSHOT_ESC 3

# Set DShot Command Rate to double the loop rate ie (SCHED_LOOP_RATE)
SERVO_DSHOT_RATE 2
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# TMotor Alpha 60A ESCs
MOT_PWM_MAX 1940
MOT_PWM_MIN 1100

MOT_SPIN_ARM 0.06
MOT_SPIN_MAX 1
MOT_SPIN_MIN 0.08
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# TMotor F55A Pro II ESC

# Enable BDShot + Extended Telemetry Params
@include BDShot_Ext_BLHeli32_AM32.parm

#
MOT_SPIN_ARM 0.03
MOT_SPIN_MAX 0.98
MOT_SPIN_MIN 0.06
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@

# 6S Li-Ion values

# BATT_ARM_VOLT 19.1
# BATT_CRT_VOLT 18
# BATT_LOW_VOLT 18.6

# NOTE we must explicitly set the number of battery cells
# Setting this automatically like BetaFlight does can never work and is dangerous when using LI-Ion cells.
# BF assumes you are always starting with a fully charged packed, which obviously is not always the case
MSP_OSD_NCELLS 6
OSD_CELL_COUNT 6

# Average cell voltage below which the OSD element flashes
OSD_W_AVGCELLV 3.3
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
# DRONECAN Battery Monitoring for when using fully electric mode.
# Two batteries in parallel

# Battery 1 (DRONECAN) Voltage & Current
BATT_MONITOR 8
BATT_CAPACITY 15800
BATT_LOW_MAH 1600
BATT_LOW_VOLT 43.75

# Failsafe LOW Action is RTL
BATT_FS_LOW_ACT 2

# Battery 2 (DRONECAN)
BATT2_MONITOR 8
BATT2_CAPACITY 15800
BATT2_LOW_MAH 1600
BATT2_LOW_VOLT 43.75

# Failsafe LOW Action is RTL
BATT2_FS_LOW_ACT 2
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
# Power Monitor Voltage & Current


# Failsafe LOW Action is RTL
#BATT_FS_LOW_ACT 2

# add note later why use resting estimate for voltage fialsafe when you have accurate current cpacity used monitoring
# need to set the failsafe for BATT_(low/critical)_MAH
# BATT_FS_VOLTSRC 0

BATT_MONITOR 4

# These must be set by technicians on bring up using the Mauch Sensor parameters for each individual sensor
# BATT_CURR_MULT 0
# BATT_VOLT_MULT 0

BATT_LOW_VOLT 47.5
BATT_CAPACITY 0
BATT_LOW_MAH 0
Empty file.
Empty file.
Empty file.
Empty file.
Empty file.
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@

# Frame Class : QUAD
FRAME_CLASS 1

# Frame Type
# Most useful class types that determine the motor order around the frame
# Value : Name : Propeller Rotation Direction
# 12 : BetaFlightX : Propellers inward
# 18 : BetaFlightX Reversed : Propellers outward
FRAME_TYPE 12

# Yaw PID
ATC_ANG_YAW_P 11

# Pitch PID
ATC_RAT_PIT_D 0.0007
ATC_RAT_PIT_FLTD 50
ATC_RAT_PIT_FLTT 40
ATC_RAT_PIT_I 0.092
ATC_RAT_PIT_P 0.092

# Roll PID
ATC_RAT_RLL_D 0.0007
ATC_RAT_RLL_FLTD 50
ATC_RAT_RLL_FLTT 40
ATC_RAT_RLL_I 0.072
ATC_RAT_RLL_P 0.072

# YAW PID
ATC_RAT_YAW_D 0.012
ATC_RAT_YAW_FLTD 5
ATC_RAT_YAW_FLTE 7.5
ATC_RAT_YAW_I 0.014
ATC_RAT_YAW_P 0.14
Empty file.
Empty file.
60 changes: 60 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Asgardian_Designs/OSD/hd_zero.parm
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
# OSD Parameters
# Set OSD_TYPE to MSP_Display port : ie HDZero, Walksnail, newer DJI systems
OSD_TYPE 5

OSD1_ALTITUDE_X 45
OSD1_ARMING_X 0
OSD1_ARMING_Y 15
OSD1_BAT_VOLT_X 45
OSD1_BAT_VOLT_Y 0
OSD1_BATTBAR_EN 0
OSD1_BATTBAR_X 2
OSD1_BATTBAR_Y 2
OSD1_BATUSED_X 45
OSD1_BATUSED_Y 2
OSD1_CELLVOLT_X 25
OSD1_CELLVOLT_Y 5
OSD1_COMPASS_X 25
OSD1_COMPASS_Y 0
OSD1_CURRENT_X 45
OSD1_CURRENT_Y 1
OSD1_ENABLE 1
OSD1_FLTMODE_X 7
OSD1_FLTMODE_Y 16
OSD1_GPSLAT_X 38
OSD1_GPSLAT_Y 15
OSD1_GPSLONG_X 38
OSD1_GPSLONG_Y 16
OSD1_GSPEED_X 0
OSD1_GSPEED_Y 16
OSD1_HEADING_X 24
OSD1_HEADING_Y 1
OSD1_HOME_X 0
OSD1_HOME_Y 12
OSD1_HOMEDIR_EN 0
OSD1_HOMEDIR_X 5
OSD1_HOMEDIR_Y 5
OSD1_HOMEDIST_EN 0
OSD1_HOMEDIST_X 5
OSD1_HOMEDIST_Y 4
OSD1_HORIZON_X 25
OSD1_MESSAGE_X 13
OSD1_MESSAGE_Y 17
OSD1_POWER_EN 0
OSD1_POWER_X 0
OSD1_POWER_Y 9
OSD1_RSSI_X 0
OSD1_SATS_X 0
OSD1_SATS_Y 0
OSD1_THROTTLE_EN 0

# Set text resolution to 50x18 lines
# HDZero : Should be 1
OSD1_TXT_RES 1
OSD2_TXT_RES 1
OSD3_TXT_RES 1
OSD4_TXT_RES 1

OSD1_VSPEED_X 45
OSD1_VTX_PWR_EN 1
OSD1_VTX_PWR_X 8
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@

# FIXME
# Disable Air Mode instead set it on a switch
ACRO_OPTIONS 0

# Acro Rates
ACRO_RP_EXPO 0.3
ACRO_RP_RATE 670

# Turn off Acro Trainer which is on by default
# FIXME : Note acro trainer could be used to create BF horizon mode
ACRO_TRAINER 0

ACRO_Y_EXPO 0.3
ACRO_Y_RATE 670

# Acro yaw rate time constant,makes this quite small
# FIXME check the related vars in BF
ACRO_Y_RATE_TC 0.01

Empty file.
17 changes: 17 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Asgardian_Designs/RID/RID.parm
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# RemoteID / OpenDroneID Parameters

# TURN OFF READONLY AS THIS IS FOR DEVELOPMENT
DID_ENABLE 1
DID_OPTIONS 1
DID_MAVPORT -1
DID_CANDRIVER 1
AHRS_EKF_TYPE 3


# enforce OpenDroneID on DroneCAN. Note that we need to lock down key parameters
# to ensure the integrity of the RemoteID system
# DID_ENABLE 1 @READONLY
# DID_OPTIONS 1 @READONLY
# DID_MAVPORT -1 @READONLY
# DID_CANDRIVER 1 @READONLY
# AHRS_EKF_TYPE 3 @READONLY
29 changes: 29 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Asgardian_Designs/all_vehicles.parm
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
# Asgardian Designs
# All Vehicles Params

# Turn off arming by rudder it is dangerous for acro flying
ARMING_RUDDER 0

######### Filtering #########
# Enable the onboard FFT
# FIXME Check min and max

FFT_ENABLE 1
FFT_MAXHZ 950
FFT_MINHZ 16
FFT_NUM_FRAMES 5

# FFT_OPTIONS
# Compute the FFT after the filtering: harmonic notch and low pass filter
FFT_OPTIONS 3

# Signal to Noise Ratio in dB
FFT_SNR_REF 5

FFT_WINDOW_SIZE 128

######## RC Channel Mapping Common ########

# Flight Mode Channel setup
# ELRS asks flight mode be on channel 12
FLTMODE_CH 12
Empty file.
Empty file.

0 comments on commit 216b07c

Please sign in to comment.