Compare commits

...

78 Commits

Author SHA1 Message Date
Peter van der Perk c00ed78dda rc_input: singlewire use push_pull 2024-06-01 19:15:42 +02:00
Beat Küng ca112fea8a fix commander: make sure to count all valid mags in preflight check
Previously, if a mag was not required (not index 0 and not used by ekf),
it was not counted in num_enabled_and_valid_calibration.
If a user set SYS_HAS_MAG to e.g. 3, it would then trigger a preflight
failure, even if there were 3 calibrated and enabled mags.
2024-05-31 12:30:34 -04:00
bresch 53210dd8f3 ekf2-mag: with NE aiding, constrain heading drift only before takeoff
After takeoff, the heading is easily observable
2024-05-31 10:38:17 -04:00
bresch 3dac9af09e ekf2-mag: do not reset on WMM change when NE aiding is active
The mag field states are observed. No need to reset them.
2024-05-31 10:38:17 -04:00
bresch ee765e7859 ekf2-mag: do not reset when NE aiding is active 2024-05-31 10:38:17 -04:00
bresch 6515935b52 ekf2-mag: do not limit the earth mag field estimate
The EKF can recover from an initial bad earth mag field estimate.
Constraining the field is not necessary and can lead to an unpredicted
behavior of the filter.
Declination fusion is safe to run even when the horizontal field is 0
2024-05-31 10:38:17 -04:00
bresch 774b6ed3b8 ekf2-mag: do not use yaw emergency estimator to reset mag states
On slowly moving vehicles (e.g.: boats, rovers), the yaw estimator has
worse convergence than the main EKF. Resetting the mag states using the
yaw estimator as reference can lead to poor heading. Also, the EKF can
recover really well from initially incorrect mag states.
2024-05-31 10:38:17 -04:00
bresch c3d984703c ekf2-mag: remove immediate declination fusion after reset 2024-05-31 10:38:17 -04:00
bresch a6007e4b93 ekf2-mag: turn around update_all_states condition
Non-functional
2024-05-31 10:38:17 -04:00
bresch c11c75d32e ekf2-mag: always add process noise until initial value 2024-05-31 10:38:17 -04:00
Eric Katzfey 493c9e49db uORB: ORBSet don't allow duplicate insertion
* fixes a small memory leak in uORBManager.cpp (if using ORB_COMMUNICATOR)
2024-05-30 16:53:48 -04:00
asimopunov 42f4e02d7e bsondump: add check if bson document size is set to zero and set to decoded size (#23088) 2024-05-30 14:52:19 +02:00
Peter van der Perk cd93e2982c dshot: telemetry esc_status use sequential numbering for each motor
channel != telemetry_index, we've to count from 0 and increment for each enabled ESC
2024-05-30 04:56:42 -04:00
Peter van der Perk 7982f54a6a dshot: refactoring 2024-05-30 04:56:42 -04:00
Peter van der Perk ff6966da57 imxrt: dshot fix erpm calculation by implementing 3-bit exponent and 9-bit period 2024-05-30 04:56:42 -04:00
Peter van der Perk 3874b4c55d imxrt: move flexio irq handler to itcm 2024-05-30 04:56:42 -04:00
Peter van der Perk 5d2fda6172 dshot: bdshot fix esc offline/online checks 2024-05-30 04:56:42 -04:00
Peter van der Perk 0e41f9730f imxrt: dshot improve state machine reduce's no response count 2024-05-30 04:56:42 -04:00
Peter van der Perk f3ef0d6610 dshot: fix clearing out esc status 2024-05-30 04:56:42 -04:00
Peter van der Perk b0cb697f71 imxrt: dshot add 1060 support and use channels instead of timers 2024-05-30 04:56:42 -04:00
Peter van der Perk e2969952d3 drivers: dshot: prepare to extend for bidrectional dshot 2024-05-30 04:56:42 -04:00
Peter van der Perk 2de0af52e8 px4_fmuv6xrt: bidirectional dshot driver 2024-05-30 04:56:42 -04:00
Peize-Liu 2f4d6b6fac [Fix][hkust_nxt-dual]:board hkust_nxt-dual fix hw_config.h missing APP_RESERVATION_SIZE param (#23204) 2024-05-30 10:35:04 +02:00
Silvan Fuhrer efe2a52eb4 ROMFS: remove MIS_DIST_1WP customizations in airframes
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-05-29 21:00:35 -04:00
Silvan Fuhrer 752051470f Navigator: increase default of MIS_DIST_1WP to 10km
The previous default of 900m leads to many warnings if left
unchanged, especially if the vehicle is already in-air when
the Mission is started.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-05-29 21:00:35 -04:00
bresch 993782cffa ekf2: only trigger position timeout reset when hpos fusion is active 2024-05-29 20:49:14 -04:00
Silvan Fuhrer 0379048ad2 mavsdk_tests: increase acceptance radius for position check on offboard landing
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-05-29 20:46:26 -04:00
Eric Katzfey ae34e39b7e QuRT: Increased the size of the memory heap available to qurt platform (#23194)
* Increased the size of the memory heap available to qurt platform
2024-05-29 20:44:40 -04:00
Daniel Agar f3d152741c boards: sky-drones_smartap-airlink_default disable gyro_fft module to save flash 2024-05-29 20:38:49 -04:00
Daniel Agar b36f47535e boards: px4_fmu-v6c_default disable gyro_fft module to save flash 2024-05-29 20:38:49 -04:00
Daniel Agar a80c96e575 boards: px4_fmu-v5x_test disable payload_deliverer module to save flash 2024-05-29 20:38:49 -04:00
Per Frivik 267cb9906e integrationtests: mavros increase threshold for yaw_error_std 2024-05-29 11:11:09 -04:00
David Sidrane f655d1be9b Update px4_fmu-v6xrt Bootloader 2024-05-29 11:08:49 -04:00
David Sidrane 3beb57aae1 px4_fmu-v6xrt & bootloader:Bootloader enusres that ITCM memory is writable before jump to APP 2024-05-29 11:08:49 -04:00
David Sidrane d79c5f170b bootloader/common/bl.c:Fixed Wrong vec_base caculation - only effects imxrt 2024-05-29 11:08:49 -04:00
David Sidrane 04e0d3475f nxp/imxrt_common/main:Fix Breakage from a9962dc 2024-05-29 11:08:49 -04:00
Matthias Grob daa89ba30a Jankinsfile-compile: add missing comma after ark_pi6x_default 2024-05-29 15:42:41 +02:00
Jacob Dahl a4650fd70d HealthCheck: added health check for logger to report if it's running (#22781) 2024-05-29 11:56:50 +02:00
Hamish Willee b5627f487f camera_trigger: module docs for camera trigger driver (#23104) 2024-05-29 11:37:27 +02:00
Matthias Grob d1db0addf9 CameraFeedback: shorten line length such that documentation parser works
This broke in 4f64acb352 and was also flagged by CI in the pr and since then.
2024-05-29 11:24:53 +02:00
Silvan Fuhrer 032ae69eee VTOL: remove _dt passing as it's no longer used (and was wrong)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-05-28 14:54:33 +02:00
Silvan Fuhrer f8fe7c7aa3 VTOL Standard: fix transition pusher motor slew rate
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-05-28 14:54:33 +02:00
Matthias Grob dfee9ca4c6 MAVLink: remove never used _mavlink_link_termination_allowed 2024-05-28 10:41:00 +02:00
Silvan Fuhrer 1206005ed2 RTL_status: improve comment
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-05-27 12:03:16 +02:00
Silvan Fuhrer 42bca65cbf RTL_mission_reverse: start from previous WP if RTL is triggered while in Mission
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-05-27 12:03:16 +02:00
Silvan Fuhrer b9d3b9f211 RTL_mission_fast: continue mission if RTL is triggered while in Mission
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-05-27 12:03:16 +02:00
bresch f9e2ab8d44 msg-rates-setpoint: fix frame name NED -> FRD 2024-05-27 09:35:34 +02:00
Jacob Dahl da35c4adce cdcacm_autostart: handle USB power only (#23183) 2024-05-25 17:16:34 -06:00
bresch ccbcbbe268 wind_est_replay: report scale instead of inverse_scale
The estimator internally estimates the scale inverse, but the interface
should be the scale as "airspeed_corrected = scale * airspeed"
2024-05-24 17:25:39 +02:00
Hamish Willee 4f64acb352 Docs for camera_feedback module (#23103)
* Docs for camera_feedback module

* Update src/modules/camera_feedback/CameraFeedback.cpp

* Update src/modules/camera_feedback/CameraFeedback.cpp
2024-05-23 08:44:34 +10:00
Beat Küng e1ffc2cdaa commander: add check for 5V overcurrent 2024-05-22 09:34:04 +02:00
Julian Oes a9962dc44d boards: update all bootloaders 2024-05-22 18:18:55 +12:00
Julian Oes 5bace785e0 px_uploader: catch serial exception correctly
Signed-off-by: Julian Oes <julian@oes.ch>
2024-05-22 18:18:55 +12:00
Julian Oes e4fd80b6ef bootloader: remove unused/duplicate defines 2024-05-22 18:18:55 +12:00
Julian Oes 6ebb2b33df bootloader: track ArduPilot protocol
Just so we don't conflict on these commands in the future.
2024-05-22 18:18:55 +12:00
Julian Oes 8fe8f2fcb3 px_uploader.py: clean up various tidbits
Includes:
- Remove some of the outdated Python2 checks and compatibility.
- Try not catch all exceptions but only the expected ones. Otherwise,
  this makes it really hard to debug if anything unexpected actually
  goes wrong.
- Make use of fstrings.
- Make output slightly prettier.

Signed-off-by: Julian Oes <julian@oes.ch>
2024-05-22 18:18:55 +12:00
Julian Oes 7c4507b6d6 bootloader: add bootloader version
This adds a new protocol extension which allows to get the bootloader
version.

The bootloader version is different from the bootloader protocol
revision which has stabilized at 5 and is not easy to update unless a
bootloader is actually breaking the protocol. The reason being that both
the Python script as well as the uploader used in QGC will not attempt
to load firmware if they don't know the bootloader version, so it could
basically be considered a "breaking" protocol revision.

Signed-off-by: Julian Oes <julian@oes.ch>
2024-05-22 18:18:55 +12:00
Julian Oes 21e550fdba tools/bootloader: add force-erase option
If the STM32H7 fails to program or erase a full chunk of 256 bytes, the
ECC check will trigger a busfault when trying to read from it.

To speed up erasing and optimize wear, we read before erasing to check
if it actually needs erasing. That's when a busfault happens and the
erase time outs.

The workaround is to add an option to do a full erase without check.

Credit goes to:
https://github.com/ArduPilot/ardupilot/pull/22090

And the protocol option added to the bootloader is the same as for
ArduPilot, so compatible.

Signed-off-by: Julian Oes <julian@oes.ch>
2024-05-22 18:18:55 +12:00
Jacob Dahl 4a13e495d7 boards: ark: pi6x: CONFIG_DRIVERS_CDCACM_AUTOSTART=y (#23163) 2024-05-21 19:49:40 -06:00
Konrad 664a0f2cda HomePosition: Add minimum position change needed to be recognised as new home position 2024-05-21 09:11:56 +02:00
alexklimaj 1c213fa760 boards: arkv6x ark_pi6x change mavlink dialect to development 2024-05-20 16:07:34 -04:00
Jacob Dahl e72ecdbefb drivers/imu: new Murata SCH16T IMU driver (#22914)
---------

Co-authored-by: alexklimaj <alex@arkelectron.com>
2024-05-20 14:38:19 -04:00
Jacob Dahl 70304fe715 [mavlink] Parameter to always start on USB (#22234)
* usb: Added parameter to enable always starting mavlink on USB.

    Refactored cdcacm_init into a module and added a paramter to allow always starting mavlink on
    USB, also added a paramter to choose the mode. The current default behavior is to wait and listen
    for data on USB and auto-detect the protocol (mavlink, nsh, ublox). This results in the mavlink
    stream not starting until something else on the mavlink network sends a packet first. The new
    default behavior is to always start mavlink.

    Added parameters
    MAV_USB_ENABLE -- default 1 (always start mavlink on USB)
    MAV_USE_MODE -- default 3 (onboard)

* added 3 retries for opening serial port in mavlink, removed sleep before sercon

* added DRIVERS_CDCACM_AUTOSTART to ark-v6x default.px4board

* added CONFIG_DRIVERS_CDCACM_AUTOSTART=y to default.px4board for boards with CONFIG_CDCACM in their nsh/defconfig

* format

* remove PGA460 from COMMON_DISTANCE_SENSOR to save flash

* remove LIS2MDL from COMMON_MAGNETOMETER to save flash

* disable CONFIG_DRIVERS_CDCACM_AUTOSTART for fmu-v5 protected.px4board

* moved and renamed parameters, removed mode logic in mavlink

* changed parameter names, added mode none

* remove parameters from mavlink
2024-05-20 12:35:29 -06:00
Peter van der Perk 6b0ac49daf hardfault_log: Add jump to 0x0 & write 0x0 faults 2024-05-17 14:43:23 -04:00
Peter van der Perk ebfa53286f dronecan: SocketCAN driver check size before copying
Avoids memory corruption if we get packets to big
2024-05-17 14:39:52 -04:00
Peter van der Perk 470bea9ba8 Update NuttX
Fixes imxrt1170 mpu config for extra checks
2024-05-17 14:32:43 -04:00
Daniel Agar d359f6236e ekf2: symforce zero more efficiently (#23133)
- increase symforce CppConfig zero_initialization_sparsity_threshold so
   that a Matrix setZero() call is performed instead of individually zeroing

Co-authored-by: bresch <brescianimathieu@gmail.com>
2024-05-17 11:20:30 +02:00
bresch ea39032b45 mag_ctrl: combine common conditions for mag_hdg and mag_3d 2024-05-17 11:19:04 +02:00
bresch d796009302 mag_ctrl: do not fuse synthetic mag but do not zero the innovation 2024-05-17 11:19:04 +02:00
Daniel Agar bb5dfc7d51 integrationtests: mavros/mission_test.py bump yaw_error_std threshold (heading init is delayed, but not wrong) 2024-05-17 11:19:04 +02:00
Daniel Agar 5173830718 ekf2: mag fusion don't update all states or tilt by default
- cleanup some of the legacy mag flags
2024-05-17 11:19:04 +02:00
Daniel Agar bfc39cf341 ekf2: mag control always populate estimator aid src 2024-05-17 11:19:04 +02:00
Daniel Agar 95ae5a657d ekf2: merge mag_3d_control + mag_control 2024-05-17 11:19:04 +02:00
bresch b42799fac2 wind_est_replay: allow setting the initial scale factor 2024-05-17 09:17:08 +02:00
bresch 440465702e wind_est_replay: fix cov matrix format and data indexing 2024-05-17 09:17:08 +02:00
fury1895 6a966ab065 px4/fmu-v6x: set mavlink dialect to development 2024-05-17 07:51:14 +02:00
Alexis Guijarro 5fe955c243 mRo Control Zero Classic: Definition for GPS2 by default added 2024-05-16 09:45:33 -07:00
alexklimaj ecf4af7cf7 boards: ark cannode add ADIS16507 driver 2024-05-16 09:56:25 -04:00
192 changed files with 4012 additions and 1432 deletions
+1 -1
View File
@@ -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
View File
@@ -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"
@@ -24,7 +24,6 @@ param set-default FW_RR_P 0.085
param set-default FW_W_EN 1
param set-default MIS_TAKEOFF_ALT 20
param set-default MIS_DIST_1WP 2500
param set-default NAV_ACC_RAD 15
param set-default NAV_DLL_ACT 2
@@ -24,7 +24,6 @@ param set-default FW_RR_P 0.085
param set-default FW_W_EN 1
param set-default MIS_TAKEOFF_ALT 20
param set-default MIS_DIST_1WP 2500
param set-default NAV_ACC_RAD 15
param set-default NAV_DLL_ACT 2
@@ -24,7 +24,6 @@ param set-default FW_RR_P 0.085
param set-default FW_W_EN 1
param set-default MIS_TAKEOFF_ALT 20
param set-default MIS_DIST_1WP 2500
param set-default NAV_ACC_RAD 15
param set-default NAV_DLL_ACT 2
@@ -25,7 +25,6 @@ param set-default FW_W_EN 1
param set-default MIS_LTRMIN_ALT 30
param set-default MIS_TAKEOFF_ALT 20
param set-default MIS_DIST_1WP 2500
param set-default NAV_ACC_RAD 15
param set-default NAV_DLL_ACT 2
@@ -66,7 +66,6 @@ param set-default MC_PITCHRATE_I 0.05
param set-default MC_YAWRATE_MAX 20
param set-default MC_AIRMODE 1
param set-default MIS_DIST_1WP 100
param set-default MIS_TAKEOFF_ALT 15
param set-default MPC_XY_P 0.8
+6
View File
@@ -138,6 +138,12 @@ then
adis16507 -S start
fi
# SCH16T spi external IMU
if param compare -s SENS_EN_SCH16T 1
then
sch16t -S start
fi
# Eagle Tree airspeed sensor external I2C
if param compare -s SENS_EN_ETSASPD 1
then
+15
View File
@@ -123,6 +123,13 @@ else
set PARAM_FILE /fs/mtd_params
fi
# Check if /fs/mtd_params is a valid BSON file
if ! bsondump docsize /fs/mtd_caldata
then
echo "New /fs/mtd_caldata size is:"
bsondump docsize /fs/mtd_caldata
fi
#
# Load parameters.
#
@@ -439,6 +446,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)
#
@@ -54,12 +54,21 @@ def extract_timer_from_channel(line, timer_names):
return None
def imxrt_is_dshot(line):
# NXP FlexPWM format format: initIOPWM(PWM::FlexPWM2),
search = re.search('(initIOPWMDshot)', line, re.IGNORECASE)
if search:
return True
return False
def get_timer_groups(timer_config_file, verbose=False):
with open(timer_config_file, 'r') as f:
timer_config = f.read()
# timers
dshot_support = {} # key: timer
dshot_support = {str(i): False for i in range(16)}
timers_start_marker = 'io_timers_t io_timers'
timers_start = timer_config.find(timers_start_marker)
if timers_start == -1:
@@ -78,10 +87,9 @@ def get_timer_groups(timer_config_file, verbose=False):
if timer_type == 'imxrt':
if verbose: print('imxrt timer found')
timer_names.append(timer)
if imxrt_is_dshot(line):
dshot_support[str(len(timers))] = True
timers.append(str(len(timers)))
dshot_support = {str(i): False for i in range(16)}
for i in range(8): # First 8 channels support dshot
dshot_support[str(i)] = True
elif timer:
if verbose: print('found timer def: {:}'.format(timer))
dshot_support[timer] = 'DMA' in line
+1 -1
View File
@@ -15,7 +15,7 @@ class ModuleDocumentation(object):
# TOC in https://github.com/PX4/PX4-user_guide/blob/main/en/SUMMARY.md
valid_categories = ['driver', 'estimator', 'controller', 'system',
'communication', 'command', 'template', 'simulation', 'autotune']
valid_subcategories = ['', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor',
valid_subcategories = ['', 'camera', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor',
'magnetometer', 'baro', 'optical_flow', 'rpm_sensor', 'transponder']
max_line_length = 80 # wrap lines that are longer than this
+76 -49
View File
@@ -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
+1
View File
@@ -14,6 +14,7 @@ CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_COMMON_HYGROMETERS=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IRLOCK=y
+3
View File
@@ -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
@@ -18,6 +19,7 @@ CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_HEATER=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y
CONFIG_DRIVERS_IMU_MURATA_SCH16T=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y
@@ -57,6 +59,7 @@ CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MAVLINK_DIALECT="development"
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
Binary file not shown.
+2
View File
@@ -8,6 +8,7 @@ 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_DSHOT=y
CONFIG_DRIVERS_GPS=y
@@ -39,6 +40,7 @@ CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MAVLINK_DIALECT="development"
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
+1
View File
@@ -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
+1
View File
@@ -7,6 +7,7 @@ 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
Binary file not shown.
+1
View File
@@ -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,6 +11,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
@@ -11,6 +11,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
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+3 -3
View File
@@ -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
+1
View File
@@ -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
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
@@ -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
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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.
+1
View File
@@ -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
+1
View File
@@ -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
@@ -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
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -9,6 +9,7 @@ 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_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_IMU_ST_L3GD20=y
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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
+1 -1
View File
@@ -8,7 +8,7 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_PAYLOAD_DELIVERER=n
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n
CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL=y
+1 -1
View File
@@ -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
@@ -47,7 +48,6 @@ CONFIG_MODULES_FW_POS_CONTROL=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
Binary file not shown.
+1
View File
@@ -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.
+2
View File
@@ -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
@@ -66,6 +67,7 @@ CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MAVLINK_DIALECT="development"
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
Binary file not shown.
+1
View File
@@ -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
@@ -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
@@ -267,6 +267,10 @@
// This is the ENET_1G interface.
/* Dshot Disambiguation *******************************************************/
#define IOMUX_DSHOT_DEFAULT (IOMUX_DRIVE_HIGHSTRENGTH | IOMUX_SLEW_FAST)
// Compile time selection
#if defined(CONFIG_ETH0_PHY_TJA1103)
# define BOARD_PHY_ADDR (18)
@@ -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
@@ -86,7 +87,6 @@ CONFIG_IMXRT_ENET=y
CONFIG_IMXRT_FLEXCAN1=y
CONFIG_IMXRT_FLEXCAN2=y
CONFIG_IMXRT_FLEXCAN3=y
CONFIG_IMXRT_FLEXIO1=y
CONFIG_IMXRT_FLEXSPI2=y
CONFIG_IMXRT_GPIO13_IRQ=y
CONFIG_IMXRT_GPIO1_0_15_IRQ=y
@@ -6,6 +6,7 @@
*(.text.board_autoled_on)
*(.text.clock_timer)
*(.text.exception_common)
*(.text.flexio_irq_handler)
*(.text.hrt_absolute_time)
*(.text.hrt_call_enter)
*(.text.hrt_tim_isr)
+1 -1
View File
@@ -114,7 +114,7 @@ const struct clock_configuration_s g_initial_clkconfig = {
.div = 1,
.mux = ACMP_CLK_ROOT_OSC_RC_48M_DIV2,
},
.flexio1_clk_root =
.flexio1_clk_root = /* 240 / 2 = 120Mhz */
{
.enable = 1,
.div = 2,
+16 -16
View File
@@ -91,14 +91,14 @@
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule0, GPIO_FLEXIO1_FLEXIO23_1, 23),
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule1, GPIO_FLEXIO1_FLEXIO25_1, 25),
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule2, GPIO_FLEXIO1_FLEXIO27_1, 27),
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule0, GPIO_FLEXIO1_FLEXIO06_1, 6),
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule1, GPIO_FLEXIO1_FLEXIO08_1, 8),
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule2, GPIO_FLEXIO1_FLEXIO10_1, 10),
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule3, GPIO_FLEXIO1_FLEXIO19_1, 19),
initIOPWMDshot(PWM::FlexPWM3, PWM::Submodule0, GPIO_FLEXIO1_FLEXIO29_1, 29),
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule0),
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule1),
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule2),
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule0),
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule1),
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule2),
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule3),
initIOPWMDshot(PWM::FlexPWM3, PWM::Submodule0),
initIOPWM(PWM::FlexPWM3, PWM::Submodule1),
initIOPWM(PWM::FlexPWM3, PWM::Submodule3),
initIOPWM(PWM::FlexPWM4, PWM::Submodule0),
@@ -106,14 +106,14 @@ constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
/* FMU_CH1 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_23),
/* FMU_CH2 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_25),
/* FMU_CH3 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_27),
/* FMU_CH4 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_06),
/* FMU_CH5 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_08),
/* FMU_CH6 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_10),
/* FMU_CH7 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_EMC_B1_19),
/* FMU_CH8 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_29),
/* FMU_CH1 */ initIOTimerChannelDshot(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_23, GPIO_FLEXIO1_FLEXIO23_1 | IOMUX_DSHOT_DEFAULT, 23),
/* FMU_CH2 */ initIOTimerChannelDshot(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_25, GPIO_FLEXIO1_FLEXIO25_1 | IOMUX_DSHOT_DEFAULT, 25),
/* FMU_CH3 */ initIOTimerChannelDshot(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_27, GPIO_FLEXIO1_FLEXIO27_1 | IOMUX_DSHOT_DEFAULT, 27),
/* FMU_CH4 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_06, GPIO_FLEXIO1_FLEXIO06_1 | IOMUX_DSHOT_DEFAULT, 6),
/* FMU_CH5 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_08, GPIO_FLEXIO1_FLEXIO08_1 | IOMUX_DSHOT_DEFAULT, 8),
/* FMU_CH6 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_10, GPIO_FLEXIO1_FLEXIO10_1 | IOMUX_DSHOT_DEFAULT, 10),
/* FMU_CH7 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_EMC_B1_19, GPIO_FLEXIO1_FLEXIO19_1 | IOMUX_DSHOT_DEFAULT, 19),
/* FMU_CH8 */ initIOTimerChannelDshot(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_29, GPIO_FLEXIO1_FLEXIO29_1 | IOMUX_DSHOT_DEFAULT, 29),
/* FMU_CH9 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_31),
/* FMU_CH10 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_EMC_B1_21),
/* FMU_CH11 */ initIOTimerChannel(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_00),
+1
View File
@@ -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
+1
View File
@@ -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
@@ -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
@@ -49,7 +50,6 @@ CONFIG_MODULES_FW_POS_CONTROL=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=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
+1
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -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_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
@@ -308,7 +308,7 @@ class MavrosMissionTest(MavrosTestCommon):
self.assertTrue(res['pitch_error_std'] < 5.0, str(res))
# TODO: fix by excluding initial heading init and reset preflight
self.assertTrue(res['yaw_error_std'] < 10.0, str(res))
self.assertTrue(res['yaw_error_std'] < 15.0, str(res))
if __name__ == '__main__':
+2
View File
@@ -9,6 +9,8 @@ uint8 BACKEND_MAVLINK = 2
uint8 BACKEND_ALL = 3
uint8 backend
bool is_logging
float32 total_written_kb # total written to log in kiloBytes
float32 write_rate_kb_s # write rate in kiloBytes/s
+5 -5
View File
@@ -8,8 +8,8 @@ bool has_vtol_approach # flag if approaches are defined for current RTL_
uint8 rtl_type # Type of RTL chosen
uint8 safe_point_index # index of the chosen safe point, if in RTL_STATUS_TYPE_DIRECT_SAFE_POINT mode
uint8 RTL_STATUS_TYPE_NONE=0 # RTL type is pending if evaluation can't pe performed currently e.g. when it is still loading the safe points
uint8 RTL_STATUS_TYPE_DIRECT_SAFE_POINT=1 # RTL type is chosen to directly go to a safe point or home position
uint8 RTL_STATUS_TYPE_DIRECT_MISSION_LAND=2 # RTL type is going straight to the beginning of the mission landing
uint8 RTL_STATUS_TYPE_FOLLOW_MISSION=3 # RTL type is following the mission from closest point to mission landing
uint8 RTL_STATUS_TYPE_FOLLOW_MISSION_REVERSE=4 # RTL type is following the mission in reverse to the start position
uint8 RTL_STATUS_TYPE_NONE=0 # pending if evaluation can't pe performed currently e.g. when it is still loading the safe points
uint8 RTL_STATUS_TYPE_DIRECT_SAFE_POINT=1 # chosen to directly go to a safe point or home position
uint8 RTL_STATUS_TYPE_DIRECT_MISSION_LAND=2 # going straight to the beginning of the mission landing
uint8 RTL_STATUS_TYPE_FOLLOW_MISSION=3 # Following the mission from start index to mission landing. Start index is current WP if in Mission mode, and closest WP otherwise.
uint8 RTL_STATUS_TYPE_FOLLOW_MISSION_REVERSE=4 # Following the mission in reverse from start index to the beginning of the mission. Start index is previous WP if in Mission mode, and closest WP otherwise.
+1 -1
View File
@@ -1,6 +1,6 @@
uint64 timestamp # time since system start (microseconds)
# body angular rates in NED frame
# body angular rates in FRD frame
float32 roll # [rad/s] roll rate setpoint
float32 pitch # [rad/s] pitch rate setpoint
float32 yaw # [rad/s] yaw rate setpoint
+5
View File
@@ -62,6 +62,11 @@ public:
{
Node **p;
// Don't allow duplicates to be inserted
if (find(node_name)) {
return;
}
if (_top == nullptr) {
p = &_top;

Some files were not shown because too many files have changed in this diff Show More