mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 19:47:35 +08:00
Compare commits
52 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| 93eef0c787 | |||
| dd5e81470c | |||
| 1d06f62399 | |||
| f5f7dfc45e | |||
| cf1c03e412 | |||
| 30e763b678 | |||
| fe26cdebc0 | |||
| 631f36b1ee | |||
| 96cddf5ed1 | |||
| 5216453b39 | |||
| 3dc97908db | |||
| 762d87285c | |||
| 5216d5c569 | |||
| 920005a235 | |||
| 50dd011c5e | |||
| e00101b771 | |||
| c8fedda09a | |||
| de07e2bef0 | |||
| 9a422dbfe8 | |||
| e2558046b8 | |||
| 00b6df1de5 | |||
| 061373f45b | |||
| f3787708d7 | |||
| 4fe51d4911 | |||
| 71bf06af56 | |||
| 5f2568231d | |||
| ce9109cf5e | |||
| ec2c91fa90 | |||
| 9f07f2a076 | |||
| 9dc3f6ea12 | |||
| 0d957e9e87 | |||
| 62e61a3d7e | |||
| cc83186dcc | |||
| eb9fd7ec76 | |||
| d8655fdde9 | |||
| d8b6b2a5ad | |||
| ef9b1b75c3 | |||
| f10650e114 | |||
| 82a259cebe | |||
| 5903a815b7 | |||
| b5e5b2a186 | |||
| 901ac16583 | |||
| 27ed745b95 | |||
| 0ca57a5547 | |||
| d182b202c8 | |||
| 192bbd177b | |||
| bb1f104a1a | |||
| e173520273 | |||
| b8e43e1649 | |||
| a59b6fe5e9 | |||
| 3b0a712c70 | |||
| 60138da56b |
@@ -47,7 +47,7 @@ pipeline {
|
||||
"ark_fmu-v6x_bootloader",
|
||||
"ark_fmu-v6x_default",
|
||||
"ark_pi6x_bootloader",
|
||||
"ark_pi6x_default"
|
||||
"ark_pi6x_default",
|
||||
"atl_mantis-edu_default",
|
||||
"av_x-v1_default",
|
||||
"bitcraze_crazyflie21_default",
|
||||
|
||||
+4
-2
@@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2017 - 2022 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2017 - 2024 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@@ -132,7 +132,9 @@ list(GET VERSION_LIST 2 PX4_VERSION_PATCH)
|
||||
string(REPLACE "-" ";" PX4_VERSION_PATCH ${PX4_VERSION_PATCH})
|
||||
list(GET PX4_VERSION_PATCH 0 PX4_VERSION_PATCH)
|
||||
|
||||
message(STATUS "PX4 version: ${PX4_GIT_TAG} (${PX4_VERSION_MAJOR}.${PX4_VERSION_MINOR}.${PX4_VERSION_PATCH})")
|
||||
# # Capture only the hash part after 'g'
|
||||
string(REGEX MATCH "g([a-f0-9]+)$" GIT_HASH "${PX4_GIT_TAG}")
|
||||
set(PX4_GIT_HASH ${CMAKE_MATCH_1})
|
||||
|
||||
define_property(GLOBAL PROPERTY PX4_MODULE_LIBRARIES
|
||||
BRIEF_DOCS "PX4 module libs"
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 - 2020 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2015 - 2024 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@@ -323,7 +323,32 @@ px4io_update:
|
||||
cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin
|
||||
git status
|
||||
|
||||
bootloaders_update: ark_fmu-v6x_bootloader cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader holybro_kakuteh7_bootloader matek_h743_bootloader matek_h743-mini_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-classic_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6c_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader
|
||||
bootloaders_update: \
|
||||
ark_fmu-v6x_bootloader \
|
||||
ark_pi6x_bootloader \
|
||||
cuav_nora_bootloader \
|
||||
cuav_x7pro_bootloader \
|
||||
cubepilot_cubeorange_bootloader \
|
||||
cubepilot_cubeorangeplus_bootloader \
|
||||
hkust_nxt-dual_bootloader \
|
||||
hkust_nxt-v1_bootloader \
|
||||
holybro_durandal-v1_bootloader \
|
||||
holybro_kakuteh7_bootloader \
|
||||
holybro_kakuteh7mini_bootloader \
|
||||
holybro_kakuteh7v2_bootloader \
|
||||
matek_h743_bootloader \
|
||||
matek_h743-mini_bootloader \
|
||||
matek_h743-slim_bootloader \
|
||||
modalai_fc-v2_bootloader \
|
||||
mro_ctrl-zero-classic_bootloader \
|
||||
mro_ctrl-zero-h7_bootloader \
|
||||
mro_ctrl-zero-h7-oem_bootloader \
|
||||
mro_pixracerpro_bootloader \
|
||||
px4_fmu-v6c_bootloader \
|
||||
px4_fmu-v6u_bootloader \
|
||||
px4_fmu-v6x_bootloader \
|
||||
px4_fmu-v6xrt_bootloader \
|
||||
siyi_n7_bootloader
|
||||
git status
|
||||
|
||||
.PHONY: coverity_scan
|
||||
|
||||
@@ -439,6 +439,14 @@ else
|
||||
# Must be started after the serial config is read
|
||||
rc_input start $RC_INPUT_ARGS
|
||||
|
||||
# Manages USB interface
|
||||
if ! cdcacm_autostart start
|
||||
then
|
||||
sercon
|
||||
echo "Starting MAVLink on /dev/ttyACM0"
|
||||
mavlink start -d /dev/ttyACM0
|
||||
fi
|
||||
|
||||
#
|
||||
# Play the startup tune (if not disabled or there is an error)
|
||||
#
|
||||
|
||||
+76
-49
@@ -1,7 +1,7 @@
|
||||
#!/usr/bin/env python3
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2012-2024 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@@ -50,9 +50,6 @@
|
||||
# Currently only used for informational purposes.
|
||||
#
|
||||
|
||||
# for python2.7 compatibility
|
||||
from __future__ import print_function
|
||||
|
||||
import sys
|
||||
import argparse
|
||||
import binascii
|
||||
@@ -70,35 +67,32 @@ from sys import platform as _platform
|
||||
try:
|
||||
import serial
|
||||
except ImportError as e:
|
||||
print("Failed to import serial: " + str(e))
|
||||
print(f"Failed to import serial: {e}")
|
||||
print("")
|
||||
print("You may need to install it using:")
|
||||
print(" pip3 install --user pyserial")
|
||||
print(" python -m pip install pyserial")
|
||||
print("")
|
||||
sys.exit(1)
|
||||
|
||||
|
||||
# Define time to use time.time() by default
|
||||
def _time():
|
||||
return time.time()
|
||||
|
||||
# Detect python version
|
||||
if sys.version_info[0] < 3:
|
||||
runningPython3 = False
|
||||
else:
|
||||
runningPython3 = True
|
||||
if sys.version_info[1] >=3:
|
||||
# redefine to use monotonic time when available
|
||||
def _time():
|
||||
try:
|
||||
return time.monotonic()
|
||||
except Exception:
|
||||
return time.time()
|
||||
raise RuntimeError("Python 2 is not supported. Please try again using Python 3.")
|
||||
sys.exit(1)
|
||||
|
||||
|
||||
# Use monotonic time where available
|
||||
def _time():
|
||||
try:
|
||||
return time.monotonic()
|
||||
except Exception:
|
||||
return time.time()
|
||||
|
||||
class FirmwareNotSuitableException(Exception):
|
||||
def __init__(self, message):
|
||||
super(FirmwareNotSuitableException, self).__init__(message)
|
||||
|
||||
|
||||
class firmware(object):
|
||||
'''Loads a firmware file'''
|
||||
|
||||
@@ -163,13 +157,13 @@ class firmware(object):
|
||||
|
||||
def crc(self, padlen):
|
||||
state = self.__crc32(self.image, int(0))
|
||||
for i in range(len(self.image), (padlen - 1), 4):
|
||||
for _ in range(len(self.image), (padlen - 1), 4):
|
||||
state = self.__crc32(self.crcpad, state)
|
||||
return state
|
||||
|
||||
|
||||
class uploader(object):
|
||||
'''Uploads a firmware file to the PX FMU bootloader'''
|
||||
class uploader:
|
||||
'''Uploads a firmware file to the PX4 bootloader'''
|
||||
|
||||
# protocol bytes
|
||||
INSYNC = b'\x12'
|
||||
@@ -195,6 +189,8 @@ class uploader(object):
|
||||
GET_CHIP = b'\x2c' # rev5+ , get chip version
|
||||
SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay
|
||||
GET_CHIP_DES = b'\x2e' # rev5+ , get chip description in ASCII
|
||||
GET_VERSION = b'\x2f' # rev5+ , get chip description in ASCII
|
||||
CHIP_FULL_ERASE = b'\x40' # full erase of flash, rev6+
|
||||
MAX_DES_LENGTH = 20
|
||||
|
||||
REBOOT = b'\x30'
|
||||
@@ -205,6 +201,7 @@ class uploader(object):
|
||||
INFO_BOARD_ID = b'\x02' # board type
|
||||
INFO_BOARD_REV = b'\x03' # board revision
|
||||
INFO_FLASH_SIZE = b'\x04' # max firmware size in bytes
|
||||
BL_VERSION = b'\x07' # get bootloader version, e.g. major.minor.patch.githash (up to 20 chars)
|
||||
|
||||
PROG_MULTI_MAX = 252 # protocol max is 255, must be multiple of 4
|
||||
READ_MULTI_MAX = 252 # protocol max is 255
|
||||
@@ -235,6 +232,7 @@ class uploader(object):
|
||||
self.baudrate_bootloader = baudrate_bootloader
|
||||
self.baudrate_flightstack = baudrate_flightstack
|
||||
self.baudrate_flightstack_idx = -1
|
||||
self.force_erase = False
|
||||
|
||||
def close(self):
|
||||
if self.port is not None:
|
||||
@@ -357,19 +355,22 @@ class uploader(object):
|
||||
self.port.baudrate = self.baudrate_bootloader * 2.33
|
||||
except NotImplementedError as e:
|
||||
# This error can occur because pySerial on Windows does not support odd baudrates
|
||||
print(str(e) + " -> could not check for FTDI device, assuming USB connection")
|
||||
print(f"{e} -> could not check for FTDI device, assuming USB connection")
|
||||
return
|
||||
|
||||
self.__send(uploader.GET_SYNC +
|
||||
uploader.EOC)
|
||||
try:
|
||||
self.__getSync(False)
|
||||
except:
|
||||
except RuntimeError:
|
||||
# if it fails we are on a real serial port - only leave this enabled on Windows
|
||||
if sys.platform.startswith('win'):
|
||||
self.ackWindowedMode = True
|
||||
finally:
|
||||
self.port.baudrate = self.baudrate_bootloader
|
||||
try:
|
||||
self.port.baudrate = self.baudrate_bootloader
|
||||
except Exception:
|
||||
pass
|
||||
|
||||
# send the GET_DEVICE command and wait for an info parameter
|
||||
def __getInfo(self, param):
|
||||
@@ -410,6 +411,17 @@ class uploader(object):
|
||||
pieces = value.split(b",")
|
||||
return pieces
|
||||
|
||||
def __getVersion(self):
|
||||
self.__send(uploader.GET_VERSION + uploader.EOC)
|
||||
try:
|
||||
length = self.__recv_int()
|
||||
value = self.__recv(length)
|
||||
self.__getSync()
|
||||
except RuntimeError:
|
||||
# Bootloader doesn't support version call
|
||||
return "unknown"
|
||||
return value.decode()
|
||||
|
||||
def __drawProgressBar(self, label, progress, maxVal):
|
||||
if maxVal < progress:
|
||||
progress = maxVal
|
||||
@@ -421,10 +433,16 @@ class uploader(object):
|
||||
|
||||
# send the CHIP_ERASE command and wait for the bootloader to become ready
|
||||
def __erase(self, label):
|
||||
print("Windowed mode: %s" % self.ackWindowedMode)
|
||||
print(f"Windowed mode: {self.ackWindowedMode}")
|
||||
print("\n", end='')
|
||||
self.__send(uploader.CHIP_ERASE +
|
||||
uploader.EOC)
|
||||
|
||||
if self.force_erase:
|
||||
print("Trying force erase of full chip...\n")
|
||||
self.__send(uploader.CHIP_FULL_ERASE +
|
||||
uploader.EOC)
|
||||
else:
|
||||
self.__send(uploader.CHIP_ERASE +
|
||||
uploader.EOC)
|
||||
|
||||
# erase is very slow, give it 30s
|
||||
deadline = _time() + 30.0
|
||||
@@ -441,9 +459,14 @@ class uploader(object):
|
||||
|
||||
if self.__trySync():
|
||||
self.__drawProgressBar(label, 10.0, 10.0)
|
||||
if self.force_erase:
|
||||
print("\nForce erase done.\n")
|
||||
return
|
||||
|
||||
raise RuntimeError("timed out waiting for erase")
|
||||
if self.force_erase:
|
||||
raise RuntimeError("timed out waiting for erase, force erase is likely not supported by bootloader!")
|
||||
else:
|
||||
raise RuntimeError("timed out waiting for erase")
|
||||
|
||||
# send a PROG_MULTI command to write a collection of bytes
|
||||
def __program_multi(self, data, windowMode):
|
||||
@@ -581,8 +604,11 @@ class uploader(object):
|
||||
self.board_rev = self.__getInfo(uploader.INFO_BOARD_REV)
|
||||
self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)
|
||||
|
||||
self.version = self.__getVersion()
|
||||
|
||||
# upload the firmware
|
||||
def upload(self, fw_list, force=False, boot_delay=None, boot_check=False):
|
||||
def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_erase=False):
|
||||
self.force_erase = force_erase
|
||||
# select correct binary
|
||||
found_suitable_firmware = False
|
||||
for file in fw_list:
|
||||
@@ -611,6 +637,8 @@ class uploader(object):
|
||||
print("Loaded firmware for board id: %s,%s size: %d bytes (%.2f%%) " % (fw.property('board_id'), fw.property('board_revision'), fw.property('image_size'), percent))
|
||||
print()
|
||||
|
||||
print(f"Bootloader version: {self.version}")
|
||||
|
||||
# Make sure we are doing the right thing
|
||||
start = _time()
|
||||
if self.board_type != fw.property('board_id'):
|
||||
@@ -640,14 +668,14 @@ class uploader(object):
|
||||
self.otp_coa = self.otp[32:160]
|
||||
# show user:
|
||||
try:
|
||||
print("sn: ", end='')
|
||||
print("Sn: ", end='')
|
||||
for byte in range(0, 12, 4):
|
||||
x = self.__getSN(byte)
|
||||
x = x[::-1] # reverse the bytes
|
||||
self.sn = self.sn + x
|
||||
print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
|
||||
print('')
|
||||
print("chip: %08x" % self.__getCHIP())
|
||||
print("Chip: %08x" % self.__getCHIP())
|
||||
|
||||
otp_id = self.otp_id.decode('Latin-1')
|
||||
if ("PX4" in otp_id):
|
||||
@@ -657,17 +685,19 @@ class uploader(object):
|
||||
print("OTP pid: " + binascii.hexlify(self.otp_pid).decode('Latin-1'))
|
||||
print("OTP coa: " + binascii.b2a_base64(self.otp_coa).decode('Latin-1'))
|
||||
|
||||
except Exception:
|
||||
except Exception as e:
|
||||
# ignore bad character encodings
|
||||
print(f"Exception ignored: {e}")
|
||||
pass
|
||||
|
||||
# Silicon errata check was added in v5
|
||||
if (self.bl_rev >= 5):
|
||||
des = self.__getCHIPDes()
|
||||
if (len(des) == 2):
|
||||
print("family: %s" % des[0])
|
||||
print("revision: %s" % des[1])
|
||||
print("flash: %d bytes" % self.fw_maxsize)
|
||||
family, revision = des
|
||||
print(f"Family: {family.decode()}")
|
||||
print(f"Revision: {revision.decode()}")
|
||||
print(f"Flash: {self.fw_maxsize} bytes")
|
||||
|
||||
# Prevent uploads where the maximum image size of the board config is smaller than the flash
|
||||
# of the board. This is a hint the user chose the wrong config and will lack features
|
||||
@@ -678,8 +708,7 @@ class uploader(object):
|
||||
# https://github.com/PX4/Firmware/blob/master/src/drivers/boards/common/stm32/board_mcu_version.c#L125-L144
|
||||
|
||||
if self.fw_maxsize > fw.property('image_maxsize') and not force:
|
||||
raise RuntimeError("Board can accept larger flash images (%u bytes) than board config (%u bytes). Please use the correct board configuration to avoid lacking critical functionality."
|
||||
% (self.fw_maxsize, fw.property('image_maxsize')))
|
||||
raise RuntimeError(f"Board can accept larger flash images ({self.fw_maxsize} bytes) than board config ({fw.property('image_maxsize')} bytes). Please use the correct board configuration to avoid lacking critical functionality.")
|
||||
else:
|
||||
# If we're still on bootloader v4 on a Pixhawk, we don't know if we
|
||||
# have the silicon errata and therefore need to flash px4_fmu-v2
|
||||
@@ -780,16 +809,13 @@ class uploader(object):
|
||||
|
||||
|
||||
def main():
|
||||
# Python2 is EOL
|
||||
if not runningPython3:
|
||||
raise RuntimeError("Python 2 is not supported. Please try again using Python 3.")
|
||||
|
||||
# Parse commandline arguments
|
||||
parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.")
|
||||
parser.add_argument('--port', action="store", required=True, help="Comma-separated list of serial port(s) to which the FMU may be attached")
|
||||
parser.add_argument('--baud-bootloader', action="store", type=int, default=115200, help="Baud rate of the serial port (default is 115200) when communicating with bootloader, only required for true serial ports.")
|
||||
parser.add_argument('--baud-flightstack', action="store", default="57600", help="Comma-separated list of baud rate of the serial port (default is 57600) when communicating with flight stack (Mavlink or NSH), only required for true serial ports.")
|
||||
parser.add_argument('--force', action='store_true', default=False, help='Override board type check, or silicon errata checks and continue loading')
|
||||
parser.add_argument('--force-erase', action="store_true", help="Do not perform the blank check, always erase every sector of the application space")
|
||||
parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash')
|
||||
parser.add_argument('--use-protocol-splitter-format', action='store_true', help='use protocol splitter format for reboot')
|
||||
parser.add_argument('firmware', action="store", nargs='+', help="Firmware file(s)")
|
||||
@@ -867,9 +893,10 @@ def main():
|
||||
# Windows, don't open POSIX ports
|
||||
if "/" not in port:
|
||||
up = uploader(port, args.baud_bootloader, baud_flightstack)
|
||||
except Exception:
|
||||
except Exception as e:
|
||||
# open failed, rate-limit our attempts
|
||||
time.sleep(0.05)
|
||||
print(f"Exception ignored: {e}")
|
||||
|
||||
# and loop to the next port
|
||||
continue
|
||||
@@ -884,10 +911,10 @@ def main():
|
||||
up.identify()
|
||||
found_bootloader = True
|
||||
print()
|
||||
print("Found board id: %s,%s bootloader version: %s on %s" % (up.board_type, up.board_rev, up.bl_rev, port))
|
||||
print(f"Found board id: {up.board_type},{up.board_rev} bootloader protocol revision {up.bl_rev} on {port}")
|
||||
break
|
||||
|
||||
except Exception:
|
||||
except (RuntimeError, serial.SerialException):
|
||||
|
||||
if not up.send_reboot(args.use_protocol_splitter_format):
|
||||
break
|
||||
@@ -907,14 +934,14 @@ def main():
|
||||
|
||||
try:
|
||||
# ok, we have a bootloader, try flashing it
|
||||
up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay)
|
||||
up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay, force_erase=args.force_erase)
|
||||
|
||||
# if we made this far without raising exceptions, the upload was successful
|
||||
successful = True
|
||||
|
||||
except RuntimeError as ex:
|
||||
except RuntimeError as e:
|
||||
# print the error
|
||||
print("\nERROR: %s" % ex.args)
|
||||
print(f"\n\nError: {e}")
|
||||
|
||||
except FirmwareNotSuitableException:
|
||||
unsuitable_board = True
|
||||
|
||||
@@ -12,6 +12,7 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
|
||||
|
||||
@@ -8,6 +8,7 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
|
||||
Binary file not shown.
@@ -8,13 +8,16 @@ CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_HEATER=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_MEMSIC_MMC5983MA=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC=y
|
||||
CONFIG_DRIVERS_OPTICAL_FLOW_PAW3902=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
|
||||
Binary file not shown.
@@ -32,19 +32,10 @@ then
|
||||
param set-default SENS_TEMP_ID 2490378
|
||||
fi
|
||||
|
||||
param set-default EKF2_BARO_DELAY 13
|
||||
param set-default EKF2_BARO_NOISE 0.9
|
||||
param set-default EKF2_HGT_REF 2
|
||||
param set-default EKF2_MAG_DELAY 100
|
||||
param set-default EKF2_MAG_NOISE 0.06
|
||||
param set-default EKF2_MULTI_IMU 2
|
||||
param set-default EKF2_OF_CTRL 1
|
||||
param set-default EKF2_OF_DELAY 48
|
||||
param set-default EKF2_OF_N_MIN 0.05
|
||||
param set-default EKF2_RNG_A_HMAX 25
|
||||
param set-default EKF2_RNG_DELAY 48
|
||||
param set-default EKF2_RNG_NOISE 0.03
|
||||
param set-default EKF2_RNG_QLTY_T 0.1
|
||||
param set-default EKF2_RNG_SFE 0.03
|
||||
|
||||
param set-default SENS_FLOW_RATE 150
|
||||
|
||||
@@ -21,8 +21,10 @@ then
|
||||
fi
|
||||
|
||||
# Internal magnetometer on I2C
|
||||
# TODO: Write a driver for the MMC5983MA
|
||||
mmc5983ma -I -b 4 start
|
||||
if ! iis2mdc -R 4 -I -b 4 start
|
||||
then
|
||||
mmc5983ma -I -b 4 start
|
||||
fi
|
||||
|
||||
# Internal Baro on I2C
|
||||
bmp388 -I -b 4 start
|
||||
|
||||
@@ -2,6 +2,7 @@ CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_MAIERTEK_MPC2520=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
|
||||
|
||||
@@ -3,6 +3,7 @@ CONFIG_BOARD_ARCHITECTURE="cortex-m4"
|
||||
CONFIG_BOARD_CONSTRAINED_FLASH=y
|
||||
CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_BOARD_COMPILE_DEFINITIONS="-Wno-narrowing"
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_BAROMETER_LPS25H=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_CONSTRAINED_FLASH=y
|
||||
CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_BOARD_COMPILE_DEFINITIONS="-Wno-narrowing"
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L1X=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_BOSCH_BMI088_I2C=y
|
||||
|
||||
@@ -7,12 +7,14 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_HEATER=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
|
||||
|
||||
Binary file not shown.
@@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
|
||||
Binary file not shown.
@@ -11,9 +11,11 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
|
||||
|
||||
Binary file not shown.
@@ -194,6 +194,12 @@
|
||||
|
||||
#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */
|
||||
|
||||
/* UART clock selection */
|
||||
/* reset to default to overwrite any changes done by any bootloader */
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC
|
||||
#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC
|
||||
|
||||
/* FLASH wait states */
|
||||
#define BOARD_FLASH_WAITSTATES 2
|
||||
|
||||
|
||||
@@ -11,9 +11,11 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y
|
||||
|
||||
Binary file not shown.
@@ -195,6 +195,12 @@
|
||||
|
||||
#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */
|
||||
|
||||
/* UART clock selection */
|
||||
/* reset to default to overwrite any changes done by any bootloader */
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC
|
||||
#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC
|
||||
|
||||
/* FLASH wait states */
|
||||
#define BOARD_FLASH_WAITSTATES 2
|
||||
|
||||
|
||||
@@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -8,6 +8,7 @@ CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP280=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
|
||||
|
||||
@@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP280=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
|
||||
|
||||
@@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -97,9 +97,9 @@
|
||||
#define INTERFACE_USART_CONFIG "/dev/ttyS5,57600"
|
||||
#define BOOT_DELAY_ADDRESS 0x000001a0
|
||||
#define BOARD_TYPE 1013
|
||||
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
|
||||
#define BOARD_FLASH_SECTORS (15)
|
||||
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)
|
||||
#define BOARD_FLASH_SECTORS (14)
|
||||
#define BOARD_FLASH_SIZE (16 * 128 * 1024)
|
||||
#define APP_RESERVATION_SIZE (1 * 128 * 1024)
|
||||
|
||||
#define OSC_FREQ 16
|
||||
|
||||
|
||||
@@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -9,6 +9,7 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP280=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y
|
||||
|
||||
@@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
|
||||
|
||||
Binary file not shown.
@@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
|
||||
Binary file not shown.
@@ -8,6 +8,7 @@ CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
|
||||
|
||||
Binary file not shown.
@@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -12,6 +12,7 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
|
||||
Binary file not shown.
@@ -12,6 +12,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -6,4 +6,5 @@
|
||||
param set-default BAT1_V_DIV 10.1
|
||||
param set-default BAT1_A_PER_V 17
|
||||
|
||||
param set-default GPS_2_CONFIG 202
|
||||
param set-default TEL_FRSKY_CONFIG 103
|
||||
|
||||
@@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -9,6 +9,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -9,9 +9,11 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_BOSCH_BMI085=y
|
||||
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
|
||||
|
||||
Binary file not shown.
@@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -10,6 +10,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -11,6 +11,7 @@ CONFIG_DRIVERS_BAROMETER_MPL3115A2=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_SRF05=y
|
||||
|
||||
@@ -11,6 +11,7 @@ CONFIG_DRIVERS_BAROMETER_MPL3115A2=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_SRF05=y
|
||||
|
||||
@@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP280=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
|
||||
|
||||
@@ -9,6 +9,8 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
|
||||
CONFIG_DRIVERS_IMU_ST_L3GD20=y
|
||||
|
||||
@@ -11,9 +11,11 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_HEATER=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
|
||||
|
||||
@@ -11,9 +11,11 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_HEATER=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
|
||||
|
||||
@@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -10,6 +10,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -6,6 +6,7 @@ CONFIG_COMMON_OPTICAL_FLOW=n
|
||||
CONFIG_COMMON_TELEMETRY=n
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=n
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=n
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=n
|
||||
CONFIG_DRIVERS_IRLOCK=n
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
|
||||
CONFIG_DRIVERS_PWM_INPUT=n
|
||||
|
||||
@@ -14,6 +14,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -246,6 +246,12 @@
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3
|
||||
|
||||
/* UART clock selection */
|
||||
/* reset to default to overwrite any changes done by any bootloader */
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC
|
||||
#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC
|
||||
|
||||
/* ADC 1 2 3 clock source */
|
||||
|
||||
#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2
|
||||
|
||||
@@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -14,6 +14,7 @@ CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y
|
||||
CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
Binary file not shown.
@@ -250,6 +250,12 @@
|
||||
|
||||
#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2
|
||||
|
||||
/* UART clock selection */
|
||||
/* reset to default to overwrite any changes done by any bootloader */
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC
|
||||
#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC
|
||||
|
||||
/* FDCAN 1 2 clock source */
|
||||
|
||||
#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */
|
||||
|
||||
@@ -13,6 +13,7 @@ CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y
|
||||
CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
@@ -33,6 +34,7 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_PX4IO=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
@@ -84,6 +86,7 @@ CONFIG_SYSTEMCMDS_BSONDUMP=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
||||
CONFIG_SYSTEMCMDS_I2C_LAUNCHER=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_IO_BYPASS_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
|
||||
Binary file not shown.
@@ -12,9 +12,11 @@ param set-default MAV_2_RATE 100000
|
||||
param set-default MAV_2_REMOTE_PRT 14550
|
||||
param set-default MAV_2_UDP_PRT 14550
|
||||
|
||||
# By disabling all 3 INA modules, we use the
|
||||
# i2c_launcher instead.
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 1
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
safety_button start
|
||||
|
||||
|
||||
@@ -17,6 +17,7 @@
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
set HAVE_PM2 yes
|
||||
set INA_CONFIGURED no
|
||||
|
||||
if mft query -q -k MFT -s MFT_PM2 -v 0
|
||||
then
|
||||
@@ -39,6 +40,8 @@ then
|
||||
then
|
||||
ina226 -X -b 2 -t 2 -k start
|
||||
fi
|
||||
|
||||
set INA_CONFIGURED yes
|
||||
fi
|
||||
|
||||
if param compare SENS_EN_INA228 1
|
||||
@@ -49,6 +52,8 @@ then
|
||||
then
|
||||
ina228 -X -b 2 -t 2 -k start
|
||||
fi
|
||||
|
||||
set INA_CONFIGURED yes
|
||||
fi
|
||||
|
||||
if param compare SENS_EN_INA238 1
|
||||
@@ -59,6 +64,25 @@ then
|
||||
then
|
||||
ina238 -X -b 2 -t 2 -k start
|
||||
fi
|
||||
|
||||
set INA_CONFIGURED yes
|
||||
fi
|
||||
|
||||
#Start Auterion Power Module selector for Skynode boards
|
||||
if ver hwbasecmp 009 010
|
||||
then
|
||||
pm_selector_auterion start
|
||||
else
|
||||
if [ $INA_CONFIGURED = no ]
|
||||
then
|
||||
# INA226, INA228, INA238 auto-start
|
||||
i2c_launcher start -b 1
|
||||
if [ $HAVE_PM2 = yes ]
|
||||
then
|
||||
i2c_launcher start -b 2
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
# Internal SPI bus ICM42686p (hard-mounted)
|
||||
@@ -88,4 +112,5 @@ fi
|
||||
|
||||
bmp388 -X -b 2 start
|
||||
|
||||
unset INA_CONFIGURED
|
||||
unset HAVE_PM2
|
||||
|
||||
@@ -28,6 +28,7 @@ CONFIG_ARMV7M_ITCM=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU=y
|
||||
CONFIG_ARM_MPU_RESET=y
|
||||
CONFIG_BOARDCTL=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
|
||||
@@ -52,6 +52,7 @@
|
||||
#define IMXRT_IPG_PODF_DIVIDER 5
|
||||
#define BOARD_GPT_FREQUENCY 24000000
|
||||
#define BOARD_XTAL_FREQUENCY 24000000
|
||||
#define BOARD_FLEXIO_PREQ 108000000
|
||||
|
||||
/* SDIO *********************************************************************/
|
||||
|
||||
|
||||
@@ -29,6 +29,7 @@ CONFIG_ARMV7M_ITCM=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU=y
|
||||
CONFIG_ARM_MPU_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
CONFIG_BOARD_BOOTLOADER_FIXUP=y
|
||||
@@ -46,7 +47,10 @@ CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x3643
|
||||
CONFIG_CDCACM_VENDORSTR="Dronecode Project, Inc."
|
||||
CONFIG_DEBUG_ERROR=y
|
||||
CONFIG_DEBUG_FEATURES=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_MEMFAULT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
@@ -185,7 +189,6 @@ CONFIG_LPUART8_TXDMA=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_MULTIBLOCK_LIMIT=1
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
@@ -258,7 +261,6 @@ CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=2032
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDIO_BLOCKSETUP=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=32
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
@@ -277,6 +279,7 @@ CONFIG_SYSTEM_CLE=y
|
||||
CONFIG_SYSTEM_DHCPC_RENEW=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYSTEM_PING=y
|
||||
CONFIG_SYSTEM_SYSTEM=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
|
||||
@@ -455,6 +455,7 @@
|
||||
#define RC_SERIAL_SINGLEWIRE 1 // Suport Single wire wiring
|
||||
#define RC_SERIAL_SWAP_RXTX 1 // Set Swap (but not supported in HW) to use Single wire
|
||||
#define RC_SERIAL_SWAP_USING_SINGLEWIRE 1 // Set to use Single wire swap as HW does not support swap
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
/* FLEXSPI4 */
|
||||
|
||||
|
||||
@@ -114,11 +114,11 @@ const struct clock_configuration_s g_initial_clkconfig = {
|
||||
.div = 1,
|
||||
.mux = ACMP_CLK_ROOT_OSC_RC_48M_DIV2,
|
||||
},
|
||||
.flexio1_clk_root =
|
||||
.flexio1_clk_root = /* 432 / 4 = 108Mhz */
|
||||
{
|
||||
.enable = 1,
|
||||
.div = 2,
|
||||
.mux = FLEXIO1_CLK_ROOT_SYS_PLL3_DIV2,
|
||||
.div = 4,
|
||||
.mux = FLEXIO1_CLK_ROOT_SYS_PLL2_PFD3,
|
||||
},
|
||||
.flexio2_clk_root =
|
||||
{
|
||||
@@ -492,9 +492,9 @@ const struct clock_configuration_s g_initial_clkconfig = {
|
||||
.mfd = 268435455,
|
||||
.ss_enable = 0,
|
||||
.pfd0 = 27, /* (528 * 18) / 27 = 352 MHz */
|
||||
.pfd1 = 16, /* (528 * 16) / 16 = 594 MHz */
|
||||
.pfd2 = 24, /* (528 * 24) / 27 = 396 MHz */
|
||||
.pfd3 = 32, /* (528 * 32) / 27 = 297 MHz */
|
||||
.pfd1 = 16, /* (528 * 18) / 16 = 594 MHz */
|
||||
.pfd2 = 24, /* (528 * 18) / 24 = 396 MHz */
|
||||
.pfd3 = 22, /* (528 * 18) / 22 = 216 MHz */
|
||||
},
|
||||
.sys_pll3 =
|
||||
{
|
||||
|
||||
@@ -104,9 +104,10 @@ const struct flexspi_nor_config_s g_flash_fast_config = {
|
||||
.busyBitPolarity = 0u,
|
||||
.lookupTable =
|
||||
{
|
||||
/* Read */// EEH+11H+32bit addr+20dummy cycles+ 4Bytes read data //200Mhz 18 dummy=10+8
|
||||
/* Read */// EEH+11H+32bit addr+20dummy cycles+ 4Bytes read data
|
||||
/* Macronix manual says 20 dummy cycles @ 200Mhz, FlexSPI peripheral Operand value needs to be 2N in DDR mode hence 0x28 */
|
||||
[0 + 0] = FLEXSPI_LUT_SEQ(CMD_DDR, FLEXSPI_8PAD, 0xEE, CMD_DDR, FLEXSPI_8PAD, 0x11), //0x871187ee,
|
||||
[0 + 1] = FLEXSPI_LUT_SEQ(RADDR_DDR, FLEXSPI_8PAD, 0x20, DUMMY_DDR, FLEXSPI_8PAD, 0x04),//0xb3048b20,
|
||||
[0 + 1] = FLEXSPI_LUT_SEQ(RADDR_DDR, FLEXSPI_8PAD, 0x20, DUMMY_DDR, FLEXSPI_8PAD, 0x28),//0xb3288b20,
|
||||
[0 + 2] = FLEXSPI_LUT_SEQ(READ_DDR, FLEXSPI_8PAD, 0x04, STOP_EXE, FLEXSPI_1PAD, 0x00), //0xa704,
|
||||
|
||||
/* Read status */
|
||||
|
||||
@@ -53,18 +53,12 @@ static const px4_mft_device_t i2c6 = { // 24LC64T on BASE 8K 32 X 2
|
||||
|
||||
static const px4_mtd_entry_t fmum_fram = {
|
||||
.device = &qspi_flash,
|
||||
.npart = 2,
|
||||
.npart = 1,
|
||||
.partd = {
|
||||
{
|
||||
.type = MTD_PARAMETERS,
|
||||
.path = "/fs/mtd_params",
|
||||
.nblocks = 32
|
||||
},
|
||||
{
|
||||
.type = MTD_WAYPOINTS,
|
||||
.path = "/fs/mtd_waypoints",
|
||||
.nblocks = 32
|
||||
|
||||
.nblocks = 256
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
@@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP280=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
|
||||
@@ -10,6 +10,7 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_HEATER=y
|
||||
|
||||
Binary file not shown.
@@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
|
||||
@@ -364,7 +364,7 @@ __ramfunc__ void stm32_board_clockconfig(void)
|
||||
*/
|
||||
|
||||
regval = getreg32(STM32_PWR_CR3);
|
||||
regval |= STM32_PWR_CR3_LDOEN | STM32_PWR_CR3_LDOESCUEN;
|
||||
regval |= STM32_PWR_CR3_LDOEN | STM32_PWR_CR3_SCUEN;
|
||||
putreg32(regval, STM32_PWR_CR3);
|
||||
|
||||
/* Set the voltage output scale */
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user