Compare commits

..

34 Commits

Author SHA1 Message Date
fury1895 9a422dbfe8 gimbal - input_mavlink: return NoUpdate by default 2024-06-19 14:49:04 +02:00
Julian Oes e2558046b8 mavlink: enable gimbal controls in QGC over USB 2024-06-11 15:08:38 +12:00
Julian Oes 00b6df1de5 gimbal: fix auto RC and MAVLink mode
This fixes various edge cases when input is set to both: RC and
MAVLink gimbal protocol v2.

Specifically:
- We no longer immediately reset primary control if there is no update,
  otherwise this will reset immediately after an commands.
- Talking of commands: GIMBAL_MANAGER_CONFIGURE no longer switches
  control to MAVLink but only an actual incoming setpoint command does.
- And incoming setpoint command only triggers UpdatedActiveOnce which
  means we will check RC again afterwards and if there is big movement
  switch back to RC. That's the intuitive thing to do until we have
  better reporting about who/what is in control.
- Also, with RC we no longer always set us to be in control but only on
  major movement.
2024-06-11 15:08:38 +12:00
Jacob Dahl 061373f45b cdcacm_autostart: handle USB power only 2024-06-07 08:05:15 -04:00
Silvan Fuhrer f3787708d7 VTOL: remove _dt passing as it's no longer used (and was wrong)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-06-06 21:52:40 -04:00
Silvan Fuhrer 4fe51d4911 VTOL Standard: fix transition pusher motor slew rate
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-06-06 21:52:40 -04:00
Julian Oes 71bf06af56 boards: update all bootloaders 2024-06-07 09:24:40 +12:00
Peize-Liu 5f2568231d [Fix][hkust_nxt-dual]:board hkust_nxt-dual fix hw_config.h missing APP_RESERVATION_SIZE param (#23204) 2024-06-07 09:24:40 +12:00
Julian Oes ce9109cf5e Makefile: add missing bootloader targets
Quite a few were missing, and everything on one line was hard to diff.
2024-06-07 09:24:40 +12:00
David Sidrane ec2c91fa90 nxp/imxrt_common/main:Fix Breakage from a9962dc 2024-06-07 09:24:40 +12:00
Julian Oes 9f07f2a076 px_uploader: catch serial exception correctly
Signed-off-by: Julian Oes <julian@oes.ch>
2024-06-07 09:24:40 +12:00
Julian Oes 9dc3f6ea12 bootloader: remove unused/duplicate defines 2024-06-07 09:24:40 +12:00
Julian Oes 0d957e9e87 bootloader: track ArduPilot protocol
Just so we don't conflict on these commands in the future.
2024-06-07 09:24:40 +12:00
Julian Oes 62e61a3d7e 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-06-07 09:24:40 +12:00
Julian Oes cc83186dcc 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-06-07 09:24:40 +12:00
Julian Oes eb9fd7ec76 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-06-07 09:24:40 +12:00
Peter van der Perk d8655fdde9 [BACKPORT] fmu-v6xrt: Support RC telemetry 2024-06-05 11:15:45 -04:00
Peter van der Perk d8b6b2a5ad [BACKPORT] fmu-v6xrt: Fix flash configuration
Fixes correct dummy cycle count of 20
2024-06-05 11:15:45 -04:00
David Sidrane ef9b1b75c3 [BACKPORT] Update px4_fmu-v6xrt Bootloader 2024-06-05 11:15:45 -04:00
David Sidrane f10650e114 [BACKPORT] px4_fmu-v6xrt & bootloader:Bootloader enusres that ITCM memory is writable before jump to APP 2024-06-05 11:15:45 -04:00
David Sidrane 82a259cebe [BACKPORT] bootloader/common/bl.c:Fixed Wrong vec_base caculation - only effects imxrt 2024-06-05 11:15:45 -04:00
David Sidrane 5903a815b7 NuttX with imxrt:lpuart & 1170 MPU Backports
[BACKPORT] imxrt: lpuart singlewire transfer support

   These correctly enables mpu_rest on MPU init if CONFIG_ARM_MPU_RESET
   is defined.
   [BACKPORT] imxrt: 1170 MPU config ensure no lockups can occur
   [BACKPORT] armv{7|8}-{m|r}:MPU fix CONFIG naming to include ARM
2024-06-05 11:15:45 -04:00
Peter van der Perk b5e5b2a186 [BACKPORT] dronecan: SocketCAN driver check size before copying
Avoids memory corruption if we get packets to big
2024-06-05 11:15:45 -04:00
Peter van der Perk 901ac16583 [BACKPORT] fmu-v6xrt: Add I2C driver launcher 2024-06-05 11:15:45 -04:00
Peter van der Perk 27ed745b95 [BACKPORT] fmu-v6xrt: Enable debug features for more verbose hardfault output 2024-06-05 11:15:45 -04:00
David Sidrane 0ca57a5547 NuttX with imxrt_sd-preflight backport 2024-06-05 11:15:45 -04:00
David Sidrane d182b202c8 [BACKPORT] px4_fmu-v6xrt:Support_MMCSD_MULTIBLOCK with preflight 2024-06-05 11:15:45 -04:00
alexklimaj 192bbd177b airframes: dexi remove EKF2_HGT_REF default 2024-05-29 20:39:10 -04:00
alexklimaj bb1f104a1a boards: ark-pi6x remove ekf delay param defaults 2024-05-29 11:23:16 -04:00
Jacob Dahl e173520273 boards: ark: pi6x: CONFIG_DRIVERS_CDCACM_AUTOSTART=y (#23163) 2024-05-29 11:23:16 -04:00
Jacob Dahl b8e43e1649 [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-29 11:23:16 -04:00
alexklimaj a59b6fe5e9 boards: add iis2mdc mag to ark pi6x 2024-05-29 11:23:16 -04:00
Jacob Dahl 3b0a712c70 drivers/magnetometer: new ST IIS2MDC Magnetometer driver 2024-05-29 11:23:16 -04:00
Alexis Guijarro 60138da56b mRo Control Zero Classic: Definition for GPS2 by default added 2024-05-23 18:29:10 -07:00
246 changed files with 2597 additions and 4284 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",
-1
View File
@@ -15,7 +15,6 @@
"extensions": [
"chiehyu.vscode-astyle",
"dan-c-underwood.arm",
"editorconfig.editorconfig",
"fredericbonnet.cmake-test-adapter",
"github.vscode-pull-request-github",
"marus25.cortex-debug",
+1 -1
View File
@@ -1,7 +1,7 @@
root = true
[*]
insert_final_newline = true
insert_final_newline = false
[{*.{c,cpp,cc,h,hpp},CMakeLists.txt,Kconfig}]
indent_style = tab
-1
View File
@@ -4,7 +4,6 @@
"recommendations": [
"chiehyu.vscode-astyle",
"dan-c-underwood.arm",
"editorconfig.editorconfig",
"fredericbonnet.cmake-test-adapter",
"github.vscode-pull-request-github",
"marus25.cortex-debug",
+27 -2
View File
@@ -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
@@ -24,6 +24,7 @@ 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,6 +24,7 @@ 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,6 +24,7 @@ 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,6 +25,7 @@ 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,6 +66,7 @@ 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,12 +138,6 @@ 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
-7
View File
@@ -123,13 +123,6 @@ 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.
#
+1 -1
View File
@@ -6,7 +6,7 @@ function check_git_submodule {
if [[ -f $1"/.git" || -d $1"/.git" ]]; then
# always update within CI environment or configuring withing VSCode CMake where you can't interact
if [ "$CI" == "true" ] || [ -n "${VSCODE_PID+set}" ] || [ -n "${CLION_IDE+set}" ]; then
if [ "$CI" == "true" ] || [ -n "${VSCODE_PID+set}" ]; then
git submodule --quiet sync --recursive -- $1
git submodule --quiet update --init --recursive --jobs=8 -- $1 || true
git submodule --quiet sync --recursive -- $1
@@ -34,41 +34,33 @@ def extract_timer(line):
if search:
return search.group(1), 'generic'
# NXP FlexPWM format format: initIOPWM(PWM::FlexPWM2),
search = re.search('PWM::Flex([0-9a-zA-Z_]+)..PWM::Submodule([0-9])[,\)]', line, re.IGNORECASE)
# nxp rt1062 format: initIOPWM(PWM::FlexPWM2),
search = re.search('PWM::Flex([0-9a-zA-Z_]+)[,\)]', line, re.IGNORECASE)
if search:
return (search.group(1) + '_' + search.group(2)), 'imxrt'
return search.group(1), 'imxrt'
return None, 'unknown'
def extract_timer_from_channel(line, timer_names):
def extract_timer_from_channel(line, num_channels_already_found):
# Try format: initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}),
search = re.search('Timer::([0-9a-zA-Z_]+), ', line, re.IGNORECASE)
if search:
return search.group(1)
# NXP FlexPWM format: initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_B0_06),
search = re.search('PWM::(PWM[0-9]+).*PWM::Submodule([0-9])', line, re.IGNORECASE)
# nxp rt1062 format: initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_B0_06),
search = re.search('PWM::(PWM[0-9]+)[_,\)]', line, re.IGNORECASE)
if search:
return str(timer_names.index((search.group(1) + '_' + search.group(2))))
# imxrt uses a 1:1 timer group to channel association
return str(num_channels_already_found)
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 = {str(i): False for i in range(16)}
dshot_support = {} # key: timer
timers_start_marker = 'io_timers_t io_timers'
timers_start = timer_config.find(timers_start_marker)
if timers_start == -1:
@@ -77,7 +69,6 @@ def get_timer_groups(timer_config_file, verbose=False):
open_idx, close_idx = find_matching_brackets(('{', '}'), timer_config, verbose)
timers_str = timer_config[open_idx:close_idx]
timers = []
timer_names = []
for line in timers_str.splitlines():
line = line.strip()
if len(line) == 0 or line.startswith('//'):
@@ -86,11 +77,14 @@ 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)))
elif timer:
max_num_channels = 16 # Just add a fixed number of timers
timers = [str(i) for i in range(max_num_channels)]
dshot_support = {str(i): False for i in range(max_num_channels)}
for i in range(8): # First 8 channels support dshot
dshot_support[str(i)] = True
break
if timer:
if verbose: print('found timer def: {:}'.format(timer))
dshot_support[timer] = 'DMA' in line
timers.append(timer)
@@ -117,7 +111,7 @@ def get_timer_groups(timer_config_file, verbose=False):
continue
if verbose: print('--'+line+'--')
timer = extract_timer_from_channel(line, timer_names)
timer = extract_timer_from_channel(line, len(channel_timers))
if timer:
if verbose: print('Found timer: {:} in channel line {:}'.format(timer, 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 = ['', 'camera', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor',
valid_subcategories = ['', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor',
'magnetometer', 'baro', 'optical_flow', 'rpm_sensor', 'transponder']
max_line_length = 80 # wrap lines that are longer than this
@@ -6,7 +6,6 @@
param set-default CBRK_IO_SAFETY 0
param set-default CANNODE_SUB_MBD 1
param set-default CANNODE_SUB_RTCM 1
param set-default GPS_1_GNSS 63
param set-default MBE_ENABLE 1
param set-default SENS_IMU_CLPNOTI 0
+1 -1
View File
@@ -47,7 +47,7 @@
#define GPIO_BTN_SAFETY /* PB15 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN15)
/* Safety LED */
#define GPIO_LED_SAFETY /* PA1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1)
#define GPIO_LED_SAFETY /* PA1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1)
/* Tone alarm output. */
#define TONE_ALARM_TIMER 2 /* timer 2 */
-1
View File
@@ -14,7 +14,6 @@ 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
-2
View File
@@ -19,7 +19,6 @@ 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
@@ -59,7 +58,6 @@ 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
@@ -40,7 +40,6 @@ 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.
-9
View File
@@ -32,19 +32,10 @@ then
param set-default SENS_TEMP_ID 2490378
fi
param set-default EKF2_BARO_DELAY 39
param set-default EKF2_BARO_NOISE 0.9
param set-default EKF2_HGT_REF 0
param set-default EKF2_MAG_DELAY 60
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 28
param set-default EKF2_OF_N_MIN 0.05
param set-default EKF2_RNG_A_HMAX 25
param set-default EKF2_RNG_DELAY 105
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
+1 -1
View File
@@ -1,13 +1,13 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m4"
CONFIG_BOARD_ROMFSROOT="cannode"
CONFIG_BOARD_NO_HELP=y
CONFIG_BOARD_CONSTRAINED_MEMORY=y
CONFIG_DRIVERS_BAROMETER_BMP388=y
CONFIG_DRIVERS_BOOTLOADERS=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y
CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_BOARD_UAVCAN_INTERFACES=1
@@ -8,7 +8,4 @@ icm42688p -R 0 -s start
bmp388 -I -b 1 start
if ! iis2mdc -R 4 -I -b 1 start
then
bmm150 -I -b 1 start
fi
bmm150 -I -b 1 start
Binary file not shown.
Binary file not shown.
Binary file not shown.
+6 -6
View File
@@ -9,7 +9,7 @@ When running PX4 directly on the QRB5165 SoC it runs partially on the Sensor Low
The portion running on the DSP hosts the flight critical portions of PX4 such as
the IMU, barometer, magnetometer, GPS, ESC, and power management drivers, and the
state estimation. The DSP acts as the real time portion of the system. Non flight
critical applications such as Mavlink, and logging are running on the
critical applications such as Mavlink, logging, and commander are running on the
ARM CPU cluster (aka apps proc). The DSP and ARM CPU cluster communicate via a
Qualcomm proprietary shared memory interface.
@@ -27,7 +27,6 @@ The full instructions are available here:
```
px4$ boards/modalai/voxl2/scripts/run-docker.sh
root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/clean.sh
root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/build-deps.sh
root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/build-apps.sh
root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/build-slpi.sh
root@9373fa1401b8:/usr/local/workspace# exit
@@ -70,15 +69,16 @@ pxh>
## Notes
You cannot cleanly shutdown PX4 with the shutdown command on VOXL 2. You have
to power cycle the board and restart everything. Starting with SDK 1.3.0 it is possible
to cleanly shutdown PX4 on VOXL 2.
to power cycle the board and restart everything.
## Tips
Always use the latest SDK release
Start with a VOXL 2 that only has the system image installed, not the SDK
Run the command ```voxl-px4 -s``` on target to run the self-test
In order to see DSP specific debug messages the mini-dm tool in the Hexagon SDK
can be used (Most messages are passed to the apps proc but certain low level messages are not):
can be used:
```
modalai@modalai-XPS-15-9570:/local/mnt/workspace/Qualcomm/Hexagon_SDK/4.1.0.4/tools/debug/mini-dm/Ubuntu18$ sudo ./mini-dm
[sudo] password for modalai:
@@ -20,6 +20,7 @@ adb shell chmod a+x /usr/bin/voxl-px4-hitl-start
# Push configuration file
adb shell mkdir -p /etc/modalai
adb push boards/modalai/voxl2/target/voxl-px4-set-default-parameters.config /etc/modalai
adb push boards/modalai/voxl2/target/voxl-px4-fake-imu-calibration.config /etc/modalai
adb push boards/modalai/voxl2/target/voxl-px4-hitl-set-default-parameters.config /etc/modalai
+6
View File
@@ -129,6 +129,12 @@ else
DAEMON="-d"
fi
if [ ! -f /data/px4/param/parameters ]; then
echo "[INFO] Setting default parameters for PX4 on voxl"
px4 $DAEMON -s /etc/modalai/voxl-px4-set-default-parameters.config
/bin/sync
fi
if [ $SENSOR_CAL == "FAKE" ]; then
/bin/echo "[INFO] Setting up fake sensor calibration values"
px4 $DAEMON -s /etc/modalai/voxl-px4-fake-imu-calibration.config
@@ -0,0 +1,192 @@
#!/bin/sh
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
. px4-alias.sh
param select /data/px4/param/parameters
# Make sure we are running at 800Hz on IMU
param set IMU_GYRO_RATEMAX 800
# EKF2 Parameters
param set EKF2_IMU_POS_X 0.027
param set EKF2_IMU_POS_Y 0.009
param set EKF2_IMU_POS_Z -0.019
param set EKF2_EV_DELAY 5
param set EKF2_AID_MASK 280
param set EKF2_ABL_LIM 0.8
param set EKF2_TAU_POS 0.25
param set EKF2_TAU_VEL 0.25
param set MC_AIRMODE 0
param set MC_YAW_P 2.0
param set MC_YAWRATE_P 0.15
param set MC_YAWRATE_I 0.1
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_K 1.0
param set MC_PITCH_P 5.5
param set MC_PITCHRATE_P 0.08
param set MC_PITCHRATE_I 0.2
param set MC_PITCHRATE_D 0.0013
param set MC_PITCHRATE_K 1.0
param set MC_ROLL_P 5.5
param set MC_ROLLRATE_P 0.08
param set MC_ROLLRATE_I 0.2
param set MC_ROLLRATE_D 0.0013
param set MC_ROLLRATE_K 1.0
param set MPC_VELD_LP 5.0
# tweak MPC_THR_MIN to prevent roll/pitch losing control
# authority under rapid downward acceleration
param set MPC_THR_MAX 0.75
param set MPC_THR_MIN 0.08
param set MPC_THR_HOVER 0.42
param set MPC_MANTHR_MIN 0.05
# default position mode with a little expo, smooth mode is terrible
param set MPC_POS_MODE 0
param set MPC_YAW_EXPO 0.20
param set MPC_XY_MAN_EXPO 0.20
param set MPC_Z_MAN_EXPO 0.20
# max velocities
param set MPC_VEL_MANUAL 5.0
param set MPC_XY_VEL_MAX 5.0
param set MPC_XY_CRUISE 5.0
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_MAX_UP 4.0
param set MPC_LAND_SPEED 1.0
# Horizontal position PID
param set MPC_XY_P 0.95
param set MPC_XY_VEL_P_ACC 3.00
param set MPC_XY_VEL_I_ACC 0.10
param set MPC_XY_VEL_D_ACC 0.00
# Vertical position PID
# PX4 Defaults
param set MPC_Z_P 1.0
param set MPC_Z_VEL_P_ACC 8.0
param set MPC_Z_VEL_I_ACC 2.0
param set MPC_Z_VEL_D_ACC 0.0
param set MPC_TKO_RAMP_T 1.50
param set MPC_TKO_SPEED 1.50
# Set the ESC outputs to function as motors
param set VOXL_ESC_FUNC1 101
param set VOXL_ESC_FUNC2 103
param set VOXL_ESC_FUNC3 104
param set VOXL_ESC_FUNC4 102
param set VOXL_ESC_SDIR1 0
param set VOXL_ESC_SDIR2 0
param set VOXL_ESC_SDIR3 0
param set VOXL_ESC_SDIR4 0
param set VOXL_ESC_CONFIG 1
param set VOXL_ESC_REV 0
param set VOXL_ESC_MODE 0
param set VOXL_ESC_BAUD 2000000
param set VOXL_ESC_RPM_MAX 10500
param set VOXL_ESC_RPM_MIN 1000
# Set the Voxl2 IO outputs to function as motors
param set VOXL2_IO_FUNC1 101
param set VOXL2_IO_FUNC2 102
param set VOXL2_IO_FUNC3 103
param set VOXL2_IO_FUNC4 104
param set VOXL2_IO_BAUD 921600
param set VOXL2_IO_MIN 1000
param set VOXL2_IO_MAX 2000
# Some parameters for control allocation
param set CA_ROTOR_COUNT 4
param set CA_R_REV 0
param set CA_AIRFRAME 0
param set CA_ROTOR_COUNT 4
param set CA_ROTOR0_PX 0.15
param set CA_ROTOR0_PY 0.15
param set CA_ROTOR1_PX -0.15
param set CA_ROTOR1_PY -0.15
param set CA_ROTOR2_PX 0.15
param set CA_ROTOR2_PY -0.15
param set CA_ROTOR2_KM -0.05
param set CA_ROTOR3_PX -0.15
param set CA_ROTOR3_PY 0.15
param set CA_ROTOR3_KM -0.05
# Some parameter settings to disable / ignore certain preflight checks
# No GPS driver yet so disable it
param set SYS_HAS_GPS 0
# Allow arming wihtout a magnetometer (Need magnetometer driver)
param set SYS_HAS_MAG 0
param set EKF2_MAG_TYPE 5
# Allow arming without battery check (Need voxlpm driver)
param set CBRK_SUPPLY_CHK 894281
# Allow arming without an SD card
param set COM_ARM_SDCARD 0
# Allow arming wihtout CPU load information
param set COM_CPU_MAX 0.0
# Disable auto disarm. This is number of seconds to wait for takeoff
# after arming. If no takeoff happens then it will disarm. A negative
# value disables this.
param set COM_DISARM_PRFLT -1
# This parameter doesn't exist anymore. Need to see what the new method is.
# param set MAV_BROADCAST 0
# Doesn't work without setting this to Quadcopter
param set MAV_TYPE 2
# Parameters that we don't use but QGC complains about if they aren't there
param set SYS_AUTOSTART 4001
# Default RC channel mappings
param set RC_MAP_ACRO_SW 0
param set RC_MAP_ARM_SW 0
param set RC_MAP_AUX1 0
param set RC_MAP_AUX2 0
param set RC_MAP_AUX3 0
param set RC_MAP_AUX4 0
param set RC_MAP_AUX5 0
param set RC_MAP_AUX6 0
param set RC_MAP_FAILSAFE 0
param set RC_MAP_FLAPS 0
param set RC_MAP_FLTMODE 6
param set RC_MAP_GEAR_SW 0
param set RC_MAP_KILL_SW 7
param set RC_MAP_LOITER_SW 0
param set RC_MAP_MAN_SW 0
param set RC_MAP_MODE_SW 0
param set RC_MAP_OFFB_SW 0
param set RC_MAP_PARAM1 0
param set RC_MAP_PARAM2 0
param set RC_MAP_PARAM3 0
param set RC_MAP_PITCH 2
param set RC_MAP_POSCTL_SW 0
param set RC_MAP_RATT_SW 0
param set RC_MAP_RETURN_SW 0
param set RC_MAP_ROLL 1
param set RC_MAP_STAB_SW 0
param set RC_MAP_THROTTLE 3
param set RC_MAP_TRANS_SW 0
param set RC_MAP_YAW 4
param save
sleep 2
# Need px4-shutdown otherwise Linux system shutdown is called
px4-shutdown
+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_PAYLOAD_DELIVERER=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n
CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL=y
+1
View File
@@ -48,6 +48,7 @@ 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.
Binary file not shown.
-1
View File
@@ -67,7 +67,6 @@ 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.
@@ -267,10 +267,6 @@
// 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)
@@ -87,6 +87,7 @@ 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,7 +6,6 @@
*(.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
View File
@@ -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 */
+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 = /* 240 / 2 = 120Mhz */
.flexio1_clk_root =
{
.enable = 1,
.div = 2,
@@ -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 */
+16 -16
View File
@@ -91,14 +91,14 @@
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
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),
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),
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 */ 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_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_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),
Binary file not shown.
@@ -50,6 +50,7 @@ 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
@@ -86,6 +87,7 @@ CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SERIAL_TEST=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'] < 15.0, str(res))
self.assertTrue(res['yaw_error_std'] < 10.0, str(res))
if __name__ == '__main__':
+1 -1
View File
@@ -1,5 +1,5 @@
uint64 timestamp # time since system start (microseconds)
uint64 last_at_ok_timestamp # timestamp of the last "OK" received after the "AT" command
uint64 last_heartbeat # timestamp of the last successful sbd session
uint16 tx_buf_write_index # current size of the tx buffer
uint16 rx_buf_read_index # the rx buffer is parsed up to that index
uint16 rx_buf_end_index # current size of the rx buffer
+1 -1
View File
@@ -1,4 +1,4 @@
# A logging message, output with PX4_WARN, PX4_ERR, PX4_INFO
# A logging message, output with PX4_{WARN,ERR,INFO}
uint64 timestamp # time since system start (microseconds)
-2
View File
@@ -9,8 +9,6 @@ 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 # 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.
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
+1 -1
View File
@@ -1,6 +1,6 @@
uint64 timestamp # time since system start (microseconds)
# body angular rates in FRD frame
# body angular rates in NED frame
float32 roll # [rad/s] roll rate setpoint
float32 pitch # [rad/s] pitch rate setpoint
float32 yaw # [rad/s] yaw rate setpoint
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2023 PX4 Development Team. All rights reserved.
* Copyright (c) 2020 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
@@ -30,7 +30,19 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* This header defines the events::EventType type.
*/
#pragma once
#include <uORB/topics/event.h>
namespace events
{
using EventType = event_s;
} // namespace events
#include "../../../imxrt/include/px4_arch/dshot.h"
@@ -50,15 +50,3 @@
* @return 0 on success, -errno otherwise
*/
int px4_get_parameter_value(const char *option, int &value);
/**
* Parse a CLI argument to a float. There are 2 valid formats:
* - 'p:<param_name>'
* in this case the parameter is loaded from an integer parameter
* - <float>
* a floating-point value, so just a string to float conversion is done
* @param option CLI argument
* @param value returned value
* @return 0 on success, -errno otherwise
*/
int px4_get_parameter_value(const char *option, float &value);
@@ -45,7 +45,7 @@
#endif
#include <events/events_generated.h>
#include <uORB/topics/event.h>
#include <libevents_definitions.h>
#include <stdint.h>
@@ -93,7 +93,7 @@ constexpr unsigned sizeofArguments(const T &t, const Args &... args)
/**
* publish/send an event
*/
void send(event_s &event);
void send(EventType &event);
/**
* Generate event ID from an event name
@@ -109,7 +109,7 @@ constexpr uint32_t ID(const char (&name)[N])
template<typename... Args>
inline void send(uint32_t id, const LogLevels &log_levels, const char *message, Args... args)
{
event_s e{};
EventType e{};
e.log_levels = ((uint8_t)log_levels.internal << 4) | (uint8_t)log_levels.external;
e.id = id;
static_assert(util::sizeofArguments(args...) <= sizeof(e.arguments), "Too many arguments");
@@ -120,7 +120,7 @@ inline void send(uint32_t id, const LogLevels &log_levels, const char *message,
inline void send(uint32_t id, const LogLevels &log_levels, const char *message)
{
event_s e{};
EventType e{};
e.log_levels = ((uint8_t)log_levels.internal << 4) | (uint8_t)log_levels.external;
e.id = id;
CONSOLE_PRINT_EVENT(e.log_level_external, e.id, message);
@@ -89,7 +89,7 @@ static constexpr wq_config_t ttyS9{"wq:ttyS9", 1728, -30};
static constexpr wq_config_t ttyACM0{"wq:ttyACM0", 1728, -31};
static constexpr wq_config_t ttyUnknown{"wq:ttyUnknown", 1728, -32};
static constexpr wq_config_t lp_default{"wq:lp_default", 2000, -50};
static constexpr wq_config_t lp_default{"wq:lp_default", 1920, -50};
static constexpr wq_config_t test1{"wq:test1", 2000, 0};
static constexpr wq_config_t test2{"wq:test2", 2000, 0};
-46
View File
@@ -59,7 +59,6 @@ int px4_get_parameter_value(const char *option, int &value)
if (param_handle != PARAM_INVALID) {
if (param_type(param_handle) != PARAM_TYPE_INT32) {
PX4_ERR("Type of param '%s' is different from INT32", param_name);
return -EINVAL;
}
@@ -88,48 +87,3 @@ int px4_get_parameter_value(const char *option, int &value)
return 0;
}
int px4_get_parameter_value(const char *option, float &value)
{
value = 0;
/* check if this is a param name */
if (strncmp("p:", option, 2) == 0) {
const char *param_name = option + 2;
/* user wants to use a param name */
param_t param_handle = param_find(param_name);
if (param_handle != PARAM_INVALID) {
if (param_type(param_handle) != PARAM_TYPE_FLOAT) {
PX4_ERR("Type of param '%s' is different from FLOAT", param_name);
return -EINVAL;
}
float pwm_parm;
int ret = param_get(param_handle, &pwm_parm);
if (ret != 0) {
return ret;
}
value = pwm_parm;
} else {
PX4_ERR("param name '%s' not found", param_name);
return -ENXIO;
}
} else {
char *ep;
value = strtof(option, &ep);
if (*ep != '\0') {
return -EINVAL;
}
}
return 0;
}
-5
View File
@@ -62,11 +62,6 @@ public:
{
Node **p;
// Don't allow duplicates to be inserted
if (find(node_name)) {
return;
}
if (_top == nullptr) {
p = &_top;
+77 -404
View File
@@ -33,454 +33,145 @@
****************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/micro_hal.h>
#include <px4_platform_common/log.h>
#include <imxrt_flexio.h>
#include <hardware/imxrt_flexio.h>
#include <imxrt_periphclks.h>
#include <px4_arch/dshot.h>
#include <px4_arch/io_timer.h>
#include <drivers/drv_dshot.h>
#include <stdio.h>
#include "barriers.h"
#include "arm_internal.h"
#define FLEXIO_BASE IMXRT_FLEXIO1_BASE
#define FLEXIO_PREQ 120000000
#define DSHOT_TIMERS FLEXIO_SHIFTBUFNIS_COUNT
#define DSHOT_THROTTLE_POSITION 5u
#define DSHOT_TELEMETRY_POSITION 4u
#define NIBBLES_SIZE 4u
#define DSHOT_NUMBER_OF_NIBBLES 3u
#if defined(IOMUX_PULL_UP_47K)
#define IOMUX_PULL_UP IOMUX_PULL_UP_47K
#endif
static const uint32_t gcr_decode[32] = {
0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0,
0x0, 0x9, 0xA, 0xB, 0x0, 0xD, 0xE, 0xF,
0x0, 0x0, 0x2, 0x3, 0x0, 0x5, 0x6, 0x7,
0x0, 0x0, 0x8, 0x1, 0x0, 0x4, 0xC, 0x0
};
uint32_t erpms[DSHOT_TIMERS];
typedef enum {
DSHOT_START = 0,
DSHOT_12BIT_FIFO,
DSHOT_12BIT_TRANSFERRED,
DSHOT_TRANSMIT_COMPLETE,
BDSHOT_RECEIVE,
BDSHOT_RECEIVE_COMPLETE,
} dshot_state;
typedef struct dshot_handler_t {
bool init;
uint32_t data_seg1;
uint32_t irq_data;
dshot_state state;
bool bdshot;
uint32_t raw_response;
uint16_t erpm;
uint32_t crc_error_cnt;
uint32_t frame_error_cnt;
uint32_t no_response_cnt;
uint32_t last_no_response_cnt;
} dshot_handler_t;
#define BDSHOT_OFFLINE_COUNT 400 // If there are no responses for 400 setpoints ESC is offline
static dshot_handler_t dshot_inst[DSHOT_TIMERS] = {};
static uint32_t dshot_tcmp;
static uint32_t bdshot_tcmp;
static uint32_t dshot_mask;
static uint32_t bdshot_recv_mask;
static uint32_t bdshot_parsed_recv_mask;
static inline uint32_t flexio_getreg32(uint32_t offset)
{
return getreg32(FLEXIO_BASE + offset);
}
static inline void flexio_modifyreg32(unsigned int offset,
uint32_t clearbits,
uint32_t setbits)
{
modifyreg32(FLEXIO_BASE + offset, clearbits, setbits);
}
static inline void flexio_putreg32(uint32_t value, uint32_t offset)
{
putreg32(value, FLEXIO_BASE + offset);
}
static inline void enable_shifter_status_interrupts(uint32_t mask)
{
flexio_modifyreg32(IMXRT_FLEXIO_SHIFTSIEN_OFFSET, 0, mask);
}
static inline void disable_shifter_status_interrupts(uint32_t mask)
{
flexio_modifyreg32(IMXRT_FLEXIO_SHIFTSIEN_OFFSET, mask, 0);
}
static inline uint32_t get_shifter_status_flags(void)
{
return flexio_getreg32(IMXRT_FLEXIO_SHIFTSTAT_OFFSET);
}
static inline void clear_shifter_status_flags(uint32_t mask)
{
flexio_putreg32(mask, IMXRT_FLEXIO_SHIFTSTAT_OFFSET);
}
static inline void enable_timer_status_interrupts(uint32_t mask)
{
flexio_modifyreg32(IMXRT_FLEXIO_TIMIEN_OFFSET, 0, mask);
}
static inline void disable_timer_status_interrupts(uint32_t mask)
{
flexio_modifyreg32(IMXRT_FLEXIO_TIMIEN_OFFSET, mask, 0);
}
static inline uint32_t get_timer_status_flags(void)
{
return flexio_getreg32(IMXRT_FLEXIO_TIMSTAT_OFFSET);
}
static inline void clear_timer_status_flags(uint32_t mask)
{
flexio_putreg32(mask, IMXRT_FLEXIO_TIMSTAT_OFFSET);
}
static void flexio_dshot_output(uint32_t channel, uint32_t pin, uint32_t timcmp, bool inverted)
{
/* Disable Shifter */
flexio_putreg32(0, IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4);
/* No start bit, stop bit low */
flexio_putreg32(FLEXIO_SHIFTCFG_INSRC(FLEXIO_SHIFTER_INPUT_FROM_PIN) |
FLEXIO_SHIFTCFG_PWIDTH(0) |
FLEXIO_SHIFTCFG_SSTOP(FLEXIO_SHIFTER_STOP_BIT_LOW) |
FLEXIO_SHIFTCFG_SSTART(FLEXIO_SHIFTER_START_BIT_DISABLED_LOAD_DATA_ON_ENABLE),
IMXRT_FLEXIO_SHIFTCFG0_OFFSET + channel * 0x4);
/* Transmit mode, output to FXIO pin, inverted output for bdshot */
flexio_putreg32(FLEXIO_SHIFTCTL_TIMSEL(channel) |
FLEXIO_SHIFTCTL_TIMPOL(FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE) |
FLEXIO_SHIFTCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT) |
FLEXIO_SHIFTCTL_PINSEL(pin) |
FLEXIO_SHIFTCTL_PINPOL(inverted) |
FLEXIO_SHIFTCTL_SMOD(FLEXIO_SHIFTER_MODE_TRANSMIT),
IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4);
/* Start transmitting on trigger, disable on compare */
flexio_putreg32(FLEXIO_TIMCFG_TIMOUT(FLEXIO_TIMER_OUTPUT_ONE_NOT_AFFECTED_BY_RESET) |
FLEXIO_TIMCFG_TIMDEC(FLEXIO_TIMER_DEC_SRC_ON_FLEX_IO_CLOCK_SHIFT_TIMER_OUTPUT) |
FLEXIO_TIMCFG_TIMRST(FLEXIO_TIMER_RESET_NEVER) |
FLEXIO_TIMCFG_TIMDIS(FLEXIO_TIMER_DISABLE_ON_TIMER_COMPARE) |
FLEXIO_TIMCFG_TIMENA(FLEXIO_TIMER_ENABLE_ON_TRIGGER_HIGH) |
FLEXIO_TIMCFG_TSTOP(FLEXIO_TIMER_STOP_BIT_DISABLED) |
FLEXIO_TIMCFG_TSTART(FLEXIO_TIMER_START_BIT_DISABLED),
IMXRT_FLEXIO_TIMCFG0_OFFSET + channel * 0x4);
flexio_putreg32(timcmp, IMXRT_FLEXIO_TIMCMP0_OFFSET + channel * 0x4);
/* Baud mode, Trigger on shifter write */
flexio_putreg32(FLEXIO_TIMCTL_TRGSEL((4 * channel) + 1) |
FLEXIO_TIMCTL_TRGPOL(FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_LOW) |
FLEXIO_TIMCTL_TRGSRC(FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL) |
FLEXIO_TIMCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) |
FLEXIO_TIMCTL_PINSEL(0) |
FLEXIO_TIMCTL_PINPOL(FLEXIO_PIN_ACTIVE_LOW) |
FLEXIO_TIMCTL_TIMOD(FLEXIO_TIMER_MODE_DUAL8_BIT_BAUD_BIT),
IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
}
struct flexio_dev_s *flexio_s;
static int flexio_irq_handler(int irq, void *context, void *arg)
{
uint32_t flags = get_shifter_status_flags();
uint32_t channel;
for (channel = 0; flags && channel < DSHOT_TIMERS; channel++) {
if (flags & (1 << channel)) {
disable_shifter_status_interrupts(1 << channel);
uint32_t flags = flexio_s->ops->get_shifter_status_flags(flexio_s);
uint32_t instance;
if (dshot_inst[channel].state == DSHOT_START) {
dshot_inst[channel].state = DSHOT_12BIT_FIFO;
flexio_putreg32(dshot_inst[channel].irq_data, IMXRT_FLEXIO_SHIFTBUF0_OFFSET + channel * 0x4);
for (instance = 0; flags && instance < DSHOT_TIMERS; instance++) {
if (flags & (1 << instance)) {
flexio_s->ops->disable_shifter_status_interrupts(flexio_s, (1 << instance));
flexio_s->ops->disable_timer_status_interrupts(flexio_s, (1 << instance));
} else if (dshot_inst[channel].state == BDSHOT_RECEIVE) {
dshot_inst[channel].state = BDSHOT_RECEIVE_COMPLETE;
dshot_inst[channel].raw_response = flexio_getreg32(IMXRT_FLEXIO_SHIFTBUFBIS0_OFFSET + channel * 0x4);
bdshot_recv_mask |= (1 << channel);
if (bdshot_recv_mask == dshot_mask) {
// Received telemetry on all channels
// Schedule workqueue?
}
if (dshot_inst[instance].irq_data != 0) {
uint32_t buf_adr = flexio_s->ops->get_shifter_buffer_address(flexio_s, FLEXIO_SHIFTER_BUFFER, instance);
putreg32(dshot_inst[instance].irq_data, IMXRT_FLEXIO1_BASE + buf_adr);
dshot_inst[instance].irq_data = 0;
}
}
}
flags = get_timer_status_flags();
for (channel = 0; flags; (channel = (channel + 1) % DSHOT_TIMERS)) {
flags = get_timer_status_flags();
if (flags & (1 << channel)) {
clear_timer_status_flags(1 << channel);
if (dshot_inst[channel].state == DSHOT_12BIT_FIFO) {
dshot_inst[channel].state = DSHOT_12BIT_TRANSFERRED;
} else if (!dshot_inst[channel].bdshot && dshot_inst[channel].state == DSHOT_12BIT_TRANSFERRED) {
dshot_inst[channel].state = DSHOT_TRANSMIT_COMPLETE;
} else if (dshot_inst[channel].bdshot && dshot_inst[channel].state == DSHOT_12BIT_TRANSFERRED) {
disable_shifter_status_interrupts(1 << channel);
dshot_inst[channel].state = BDSHOT_RECEIVE;
/* Transmit done, disable timer and reconfigure to receive*/
flexio_putreg32(0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
/* Input data from pin, no start/stop bit*/
flexio_putreg32(FLEXIO_SHIFTCFG_INSRC(FLEXIO_SHIFTER_INPUT_FROM_PIN) |
FLEXIO_SHIFTCFG_PWIDTH(0) |
FLEXIO_SHIFTCFG_SSTOP(FLEXIO_SHIFTER_STOP_BIT_DISABLE) |
FLEXIO_SHIFTCFG_SSTART(FLEXIO_SHIFTER_START_BIT_DISABLED_LOAD_DATA_ON_SHIFT),
IMXRT_FLEXIO_SHIFTCFG0_OFFSET + channel * 0x4);
/* Shifter receive mdoe, on FXIO pin input */
flexio_putreg32(FLEXIO_SHIFTCTL_TIMSEL(channel) |
FLEXIO_SHIFTCTL_TIMPOL(FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE) |
FLEXIO_SHIFTCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) |
FLEXIO_SHIFTCTL_PINSEL(timer_io_channels[channel].dshot.flexio_pin) |
FLEXIO_SHIFTCTL_PINPOL(FLEXIO_PIN_ACTIVE_LOW) |
FLEXIO_SHIFTCTL_SMOD(FLEXIO_SHIFTER_MODE_RECEIVE),
IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4);
/* Make sure there no shifter flags high from transmission */
clear_shifter_status_flags(1 << channel);
/* Enable on pin transition, resychronize through reset on rising edge */
flexio_putreg32(FLEXIO_TIMCFG_TIMOUT(FLEXIO_TIMER_OUTPUT_ONE_AFFECTED_BY_RESET) |
FLEXIO_TIMCFG_TIMDEC(FLEXIO_TIMER_DEC_SRC_ON_FLEX_IO_CLOCK_SHIFT_TIMER_OUTPUT) |
FLEXIO_TIMCFG_TIMRST(FLEXIO_TIMER_RESET_ON_TIMER_PIN_RISING_EDGE) |
FLEXIO_TIMCFG_TIMDIS(FLEXIO_TIMER_DISABLE_ON_TIMER_COMPARE) |
FLEXIO_TIMCFG_TIMENA(FLEXIO_TIMER_ENABLE_ON_TRIGGER_BOTH_EDGE) |
FLEXIO_TIMCFG_TSTOP(FLEXIO_TIMER_STOP_BIT_ENABLE_ON_TIMER_DISABLE) |
FLEXIO_TIMCFG_TSTART(FLEXIO_TIMER_START_BIT_ENABLED),
IMXRT_FLEXIO_TIMCFG0_OFFSET + channel * 0x4);
/* Enable on pin transition, resychronize through reset on rising edge */
flexio_putreg32(bdshot_tcmp, IMXRT_FLEXIO_TIMCMP0_OFFSET + channel * 0x4);
/* Trigger on FXIO pin transition, Baud mode */
flexio_putreg32(FLEXIO_TIMCTL_TRGSEL(2 * timer_io_channels[channel].dshot.flexio_pin) |
FLEXIO_TIMCTL_TRGPOL(FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_HIGH) |
FLEXIO_TIMCTL_TRGSRC(FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL) |
FLEXIO_TIMCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) |
FLEXIO_TIMCTL_PINSEL(0) |
FLEXIO_TIMCTL_PINPOL(FLEXIO_PIN_ACTIVE_LOW) |
FLEXIO_TIMCTL_TIMOD(FLEXIO_TIMER_MODE_DUAL8_BIT_BAUD_BIT),
IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
/* Enable shifter interrupt for receiving data */
enable_shifter_status_interrupts(1 << channel);
}
}
}
return OK;
}
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot)
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq)
{
/* Calculate dshot timings based on dshot_pwm_freq */
dshot_tcmp = 0x2F00 | (((FLEXIO_PREQ / (dshot_pwm_freq * 3) / 2)) & 0xFF);
bdshot_tcmp = 0x2900 | (((FLEXIO_PREQ / (dshot_pwm_freq * 5 / 4) / 2) - 1) & 0xFF);
uint32_t timer_compare;
/* Clock FlexIO peripheral */
imxrt_clockall_flexio1();
if (dshot_pwm_freq == 150000) {
timer_compare = 0x2F8A;
/* Reset FlexIO peripheral */
flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET, 0,
FLEXIO_CTRL_SWRST_MASK);
flexio_putreg32(0, IMXRT_FLEXIO_CTRL_OFFSET);
} else if (dshot_pwm_freq == 300000) {
timer_compare = 0x2F45;
/* Initialize FlexIO peripheral */
flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET,
(FLEXIO_CTRL_DOZEN_MASK |
FLEXIO_CTRL_DBGE_MASK |
FLEXIO_CTRL_FASTACC_MASK |
FLEXIO_CTRL_FLEXEN_MASK),
(FLEXIO_CTRL_DBGE(1) |
FLEXIO_CTRL_FASTACC(1) |
FLEXIO_CTRL_FLEXEN(0)));
} else if (dshot_pwm_freq == 600000) {
timer_compare = 0x2F22;
/* FlexIO IRQ handling */
} else if (dshot_pwm_freq == 1200000) {
timer_compare = 0x2F11;
} else {
// Not supported Dshot frequency
return 0;
}
/* Init FlexIO peripheral */
flexio_s = imxrt_flexio_initialize(1);
up_enable_irq(IMXRT_IRQ_FLEXIO1);
irq_attach(IMXRT_IRQ_FLEXIO1, flexio_irq_handler, 0);
dshot_mask = 0x0;
irq_attach(IMXRT_IRQ_FLEXIO1, flexio_irq_handler, flexio_s);
for (unsigned channel = 0; (channel_mask != 0) && (channel < DSHOT_TIMERS); channel++) {
if (channel_mask & (1 << channel)) {
uint8_t timer = timer_io_channels[channel].timer_index;
if (timer_io_channels[channel].dshot.pinmux == 0) { // board does not configure dshot on this pin
if (io_timers[timer].dshot.pinmux == 0) { // board does not configure dshot on this pin
continue;
}
imxrt_config_gpio(timer_io_channels[channel].dshot.pinmux | IOMUX_PULL_UP);
imxrt_config_gpio(io_timers[timer].dshot.pinmux);
dshot_inst[channel].bdshot = enable_bidirectional_dshot;
struct flexio_shifter_config_s shft_cfg;
shft_cfg.timer_select = channel;
shft_cfg.timer_polarity = FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE;
shft_cfg.pin_config = FLEXIO_PIN_CONFIG_OUTPUT;
shft_cfg.pin_select = io_timers[timer].dshot.flexio_pin;
shft_cfg.pin_polarity = FLEXIO_PIN_ACTIVE_HIGH;
shft_cfg.shifter_mode = FLEXIO_SHIFTER_MODE_TRANSMIT;
shft_cfg.parallel_width = 0;
shft_cfg.input_source = FLEXIO_SHIFTER_INPUT_FROM_PIN;
shft_cfg.shifter_stop = FLEXIO_SHIFTER_STOP_BIT_LOW;
shft_cfg.shifter_start = FLEXIO_SHIFTER_START_BIT_DISABLED_LOAD_DATA_ON_ENABLE;
flexio_dshot_output(channel, timer_io_channels[channel].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot);
flexio_s->ops->set_shifter_config(flexio_s, channel, &shft_cfg);
struct flexio_timer_config_s tmr_cfg;
tmr_cfg.trigger_select = (4 * channel) + 1;
tmr_cfg.trigger_polarity = FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_LOW;
tmr_cfg.trigger_source = FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL;
tmr_cfg.pin_config = FLEXIO_PIN_CONFIG_OUTPUT_DISABLED;
tmr_cfg.pin_select = 0;
tmr_cfg.pin_polarity = FLEXIO_PIN_ACTIVE_LOW;
tmr_cfg.timer_mode = FLEXIO_TIMER_MODE_DUAL8_BIT_BAUD_BIT;
tmr_cfg.timer_output = FLEXIO_TIMER_OUTPUT_ONE_NOT_AFFECTED_BY_RESET;
tmr_cfg.timer_decrement = FLEXIO_TIMER_DEC_SRC_ON_FLEX_IO_CLOCK_SHIFT_TIMER_OUTPUT;
tmr_cfg.timer_reset = FLEXIO_TIMER_RESET_NEVER;
tmr_cfg.timer_disable = FLEXIO_TIMER_DISABLE_ON_TIMER_COMPARE;
tmr_cfg.timer_enable = FLEXIO_TIMER_ENABLE_ON_TRIGGER_HIGH;
tmr_cfg.timer_stop = FLEXIO_TIMER_STOP_BIT_DISABLED;
tmr_cfg.timer_start = FLEXIO_TIMER_START_BIT_DISABLED;
tmr_cfg.timer_compare = timer_compare;
flexio_s->ops->set_timer_config(flexio_s, channel, &tmr_cfg);
dshot_inst[channel].init = true;
// Mask channel to be active on dshot
dshot_mask |= (1 << channel);
}
}
flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET, 0,
FLEXIO_CTRL_FLEXEN_MASK);
flexio_s->ops->enable(flexio_s, true);
return channel_mask;
}
void up_bdshot_erpm(void)
{
uint32_t value;
uint32_t data;
uint32_t csum_data;
uint8_t exponent;
uint16_t period;
uint16_t erpm;
bdshot_parsed_recv_mask = 0;
// Decode each individual channel
for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) {
if (bdshot_recv_mask & (1 << channel)) {
value = ~dshot_inst[channel].raw_response & 0xFFFFF;
/* if lowest significant isn't 1 we've got a framing error */
if (value & 0x1) {
/* Decode RLL */
value = (value ^ (value >> 1));
/* Decode GCR */
data = gcr_decode[value & 0x1fU];
data |= gcr_decode[(value >> 5U) & 0x1fU] << 4U;
data |= gcr_decode[(value >> 10U) & 0x1fU] << 8U;
data |= gcr_decode[(value >> 15U) & 0x1fU] << 12U;
/* Calculate checksum */
csum_data = data;
csum_data = csum_data ^ (csum_data >> 8U);
csum_data = csum_data ^ (csum_data >> NIBBLES_SIZE);
if ((csum_data & 0xFU) != 0xFU) {
dshot_inst[channel].crc_error_cnt++;
} else {
data = (data >> 4) & 0xFFF;
if (data == 0xFFF) {
erpm = 0;
} else {
exponent = ((data >> 9U) & 0x7U); /* 3 bit: exponent */
period = (data & 0x1ffU); /* 9 bit: period base */
period = period << exponent; /* Period in usec */
erpm = ((1000000U * 60U / 100U + period / 2U) / period);
}
dshot_inst[channel].erpm = erpm;
bdshot_parsed_recv_mask |= (1 << channel);
dshot_inst[channel].last_no_response_cnt = dshot_inst[channel].no_response_cnt;
}
} else {
dshot_inst[channel].frame_error_cnt++;
}
}
}
}
int up_bdshot_get_erpm(uint8_t channel, int *erpm)
{
if (bdshot_parsed_recv_mask & (1 << channel)) {
*erpm = (int)dshot_inst[channel].erpm;
return 0;
}
return -1;
}
int up_bdshot_channel_status(uint8_t channel)
{
if (channel < DSHOT_TIMERS) {
return ((dshot_inst[channel].no_response_cnt - dshot_inst[channel].last_no_response_cnt) < BDSHOT_OFFLINE_COUNT);
}
return -1;
}
void up_bdshot_status(void)
{
for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) {
if (dshot_inst[channel].init) {
PX4_INFO("Channel %i %s Last erpm %i value", channel, up_bdshot_channel_status(channel) ? "online" : "offline",
dshot_inst[channel].erpm);
PX4_INFO("CRC errors Frame error No response");
PX4_INFO("%10lu %11lu %11lu", dshot_inst[channel].crc_error_cnt, dshot_inst[channel].frame_error_cnt,
dshot_inst[channel].no_response_cnt);
}
}
}
void up_dshot_trigger(void)
{
// Calc data now since we're not event driven
if (bdshot_recv_mask != 0x0) {
up_bdshot_erpm();
}
uint32_t buf_adr;
clear_timer_status_flags(0xFF);
for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) {
if (dshot_inst[channel].bdshot && (bdshot_recv_mask & (1 << channel)) == 0) {
dshot_inst[channel].no_response_cnt++;
}
if (dshot_inst[channel].init && dshot_inst[channel].data_seg1 != 0) {
flexio_putreg32(dshot_inst[channel].data_seg1, IMXRT_FLEXIO_SHIFTBUF0_OFFSET + channel * 0x4);
for (uint8_t motor_number = 0; (motor_number < DSHOT_TIMERS); motor_number++) {
if (dshot_inst[motor_number].init && dshot_inst[motor_number].data_seg1 != 0) {
buf_adr = flexio_s->ops->get_shifter_buffer_address(flexio_s, FLEXIO_SHIFTER_BUFFER, motor_number);
putreg32(dshot_inst[motor_number].data_seg1, IMXRT_FLEXIO1_BASE + buf_adr);
}
}
bdshot_recv_mask = 0x0;
clear_timer_status_flags(0xFF);
enable_shifter_status_interrupts(0xFF);
enable_timer_status_interrupts(0xFF);
flexio_s->ops->clear_timer_status_flags(flexio_s, 0xFF);
flexio_s->ops->enable_shifter_status_interrupts(flexio_s, 0xFF);
}
/* Expand packet from 16 bits 48 to get T0H and T1H timing */
uint64_t dshot_expand_data(uint16_t packet)
{
unsigned int mask;
@@ -506,22 +197,16 @@ uint64_t dshot_expand_data(uint16_t packet)
* bit 12 - dshot telemetry enable/disable
* bits 13-16 - XOR checksum
**/
void dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry)
void dshot_motor_data_set(unsigned motor_number, uint16_t throttle, bool telemetry)
{
if (channel < DSHOT_TIMERS && dshot_inst[channel].init) {
uint16_t csum_data;
if (motor_number < DSHOT_TIMERS && dshot_inst[motor_number].init) {
uint16_t packet = 0;
uint16_t checksum = 0;
packet |= throttle << DSHOT_THROTTLE_POSITION;
packet |= ((uint16_t)telemetry & 0x01) << DSHOT_TELEMETRY_POSITION;
if (dshot_inst[channel].bdshot) {
csum_data = ~packet;
} else {
csum_data = packet;
}
uint16_t csum_data = packet;
/* XOR checksum calculation */
csum_data >>= NIBBLES_SIZE;
@@ -534,20 +219,8 @@ void dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry)
packet |= (checksum & 0x0F);
uint64_t dshot_expanded = dshot_expand_data(packet);
dshot_inst[channel].data_seg1 = (uint32_t)(dshot_expanded & 0xFFFFFF);
dshot_inst[channel].irq_data = (uint32_t)(dshot_expanded >> 24);
dshot_inst[channel].state = DSHOT_START;
if (dshot_inst[channel].bdshot) {
flexio_putreg32(0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
disable_shifter_status_interrupts(1 << channel);
flexio_dshot_output(channel, timer_io_channels[channel].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot);
clear_timer_status_flags(0xFF);
}
dshot_inst[motor_number].data_seg1 = (uint32_t)(dshot_expanded & 0xFFFFFF);
dshot_inst[motor_number].irq_data = (uint32_t)(dshot_expanded >> 24);
}
}
@@ -87,6 +87,7 @@ typedef struct io_timers_t {
uint32_t clock_register; /* SIM_SCGCn */
uint32_t clock_bit; /* SIM_SCGCn bit pos */
uint32_t vectorno; /* IRQ number */
dshot_conf_t dshot;
} io_timers_t;
typedef struct io_timers_channel_mapping_element_t {
@@ -111,7 +112,6 @@ typedef struct timer_io_channels_t {
uint8_t sub_module; /* 0 based sub module offset */
uint8_t sub_module_bits; /* LDOK and CLDOK bits */
uint8_t timer_channel; /* Unused */
dshot_conf_t dshot;
} timer_io_channels_t;
#define SM0 0
@@ -255,34 +255,6 @@ static inline int channels_timer(unsigned channel)
return timer_io_channels[channel].timer_index;
}
static uint32_t get_timer_channels(unsigned timer)
{
uint32_t channels = 0;
static uint32_t channels_cache[MAX_IO_TIMERS] = {0};
if (validate_timer_index(timer) < 0) {
return channels;
} else {
if (channels_cache[timer] == 0) {
/* Gather the channel bits that belong to the timer */
uint32_t first_channel_index = io_timers_channel_mapping.element[timer].first_channel_index;
uint32_t last_channel_index = first_channel_index + io_timers_channel_mapping.element[timer].channel_count;
for (unsigned chan_index = first_channel_index; chan_index < last_channel_index; chan_index++) {
channels |= 1 << chan_index;
}
/* cache them */
channels_cache[timer] = channels;
}
}
return channels_cache[timer];
}
static uint32_t get_channel_mask(unsigned channel)
{
return io_timer_validate_channel_index(channel) == 0 ? 1 << channel : 0;
@@ -419,66 +391,41 @@ static int allocate_channel(unsigned channel, io_timer_channel_mode_t mode)
return rv;
}
static int timer_set_rate(unsigned timer, unsigned rate)
static int timer_set_rate(unsigned channel, unsigned rate)
{
int channels = get_timer_channels(timer);
irqstate_t flags = px4_enter_critical_section();
for (uint32_t channel = 0; channel < DIRECT_PWM_OUTPUT_CHANNELS; ++channel) {
if ((1 << channel) & channels) {
rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT
;
rVAL1(channels_timer(channel), timer_io_channels[channel].sub_module) = (BOARD_PWM_FREQ / rate) - 1;
rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits;
}
}
rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT
;
rVAL1(channels_timer(channel), timer_io_channels[channel].sub_module) = (BOARD_PWM_FREQ / rate) - 1;
rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits;
px4_leave_critical_section(flags);
return 0;
}
static inline void io_timer_set_oneshot_mode(unsigned timer)
static inline void io_timer_set_oneshot_mode(unsigned channel)
{
int channels = get_timer_channels(timer);
irqstate_t flags = px4_enter_critical_section();
for (uint32_t channel = 0; channel < DIRECT_PWM_OUTPUT_CHANNELS; ++channel) {
if ((1 << channel) & channels) {
uint16_t rvalue = rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module);
rvalue &= ~SMCTRL_PRSC_MASK;
rvalue |= SMCTRL_PRSC_DIV2 | SMCTRL_LDMOD;
rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT
;
rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module) = rvalue;
rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits;
}
}
uint16_t rvalue = rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module);
rvalue &= ~SMCTRL_PRSC_MASK;
rvalue |= SMCTRL_PRSC_DIV2 | SMCTRL_LDMOD;
rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT
;
rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module) = rvalue;
rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits;
px4_leave_critical_section(flags);
}
static inline void io_timer_set_PWM_mode(unsigned timer)
static inline void io_timer_set_PWM_mode(unsigned channel)
{
int channels = get_timer_channels(timer);
irqstate_t flags = px4_enter_critical_section();
for (uint32_t channel = 0; channel < DIRECT_PWM_OUTPUT_CHANNELS; ++channel) {
if ((1 << channel) & channels) {
uint16_t rvalue = rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module);
rvalue &= ~(SMCTRL_PRSC_MASK | SMCTRL_LDMOD);
rvalue |= SMCTRL_PRSC_DIV16;
rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT
;
rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module) = rvalue;
rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits;
}
}
uint16_t rvalue = rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module);
rvalue &= ~(SMCTRL_PRSC_MASK | SMCTRL_LDMOD);
rvalue |= SMCTRL_PRSC_DIV16;
rMCTRL(channels_timer(channel)) |= (timer_io_channels[channel].sub_module_bits >> MCTRL_LDOK_SHIFT) << MCTRL_CLDOK_SHIFT
;
rCTRL(channels_timer(channel), timer_io_channels[channel].sub_module) = rvalue;
rMCTRL(channels_timer(channel)) |= timer_io_channels[channel].sub_module_bits;
px4_leave_critical_section(flags);
}
@@ -583,35 +530,33 @@ int io_timer_init_timer(unsigned timer, io_timer_channel_mode_t mode)
break;
}
int channels = get_timer_channels(timer);
uint32_t first_channel_index = io_timers_channel_mapping.element[timer].first_channel_index;
uint32_t last_channel_index = first_channel_index + io_timers_channel_mapping.element[timer].channel_count;
for (uint32_t chan = 0; chan < DIRECT_PWM_OUTPUT_CHANNELS; ++chan) {
if ((1 << chan) & channels) {
for (uint32_t chan = first_channel_index; chan < last_channel_index; chan++) {
/* Clear all Faults */
rFSTS0(timer) = FSTS_FFLAG_MASK;
/* Clear all Faults */
rFSTS0(timer) = FSTS_FFLAG_MASK;
rCTRL2(timer, timer_io_channels[chan].sub_module) = SMCTRL2_CLK_SEL_EXT_CLK | SMCTRL2_DBGEN | SMCTRL2_INDEP;
rCTRL(timer, timer_io_channels[chan].sub_module) = SMCTRL_PRSC_DIV16 | SMCTRL_FULL;
/* Edge aligned at 0 */
rINIT(channels_timer(chan), timer_io_channels[chan].sub_module) = 0;
rVAL0(channels_timer(chan), timer_io_channels[chan].sub_module) = 0;
rVAL2(channels_timer(chan), timer_io_channels[chan].sub_module) = 0;
rVAL4(channels_timer(chan), timer_io_channels[chan].sub_module) = 0;
rFFILT0(timer) &= ~FFILT_FILT_PER_MASK;
rDISMAP0(timer, timer_io_channels[chan].sub_module) = 0xf000;
rDISMAP1(timer, timer_io_channels[chan].sub_module) = 0xf000;
rOUTEN(timer) |= timer_io_channels[chan].val_offset == PWMA_VAL ? OUTEN_PWMA_EN(1 << timer_io_channels[chan].sub_module)
: OUTEN_PWMB_EN(1 << timer_io_channels[chan].sub_module);
rDTSRCSEL(timer) = 0;
rMCTRL(timer) = MCTRL_LDOK(1 << timer_io_channels[chan].sub_module);
rMCTRL(timer) = timer_io_channels[chan].sub_module_bits;
}
rCTRL2(timer, timer_io_channels[chan].sub_module) = SMCTRL2_CLK_SEL_EXT_CLK | SMCTRL2_DBGEN | SMCTRL2_INDEP;
rCTRL(timer, timer_io_channels[chan].sub_module) = SMCTRL_PRSC_DIV16 | SMCTRL_FULL;
/* Edge aligned at 0 */
rINIT(channels_timer(chan), timer_io_channels[chan].sub_module) = 0;
rVAL0(channels_timer(chan), timer_io_channels[chan].sub_module) = 0;
rVAL2(channels_timer(chan), timer_io_channels[chan].sub_module) = 0;
rVAL4(channels_timer(chan), timer_io_channels[chan].sub_module) = 0;
rFFILT0(timer) &= ~FFILT_FILT_PER_MASK;
rDISMAP0(timer, timer_io_channels[chan].sub_module) = 0xf000;
rDISMAP1(timer, timer_io_channels[chan].sub_module) = 0xf000;
rOUTEN(timer) |= timer_io_channels[chan].val_offset == PWMA_VAL ? OUTEN_PWMA_EN(1 << timer_io_channels[chan].sub_module)
: OUTEN_PWMB_EN(1 << timer_io_channels[chan].sub_module);
rDTSRCSEL(timer) = 0;
rMCTRL(timer) = MCTRL_LDOK(1 << timer_io_channels[chan].sub_module);
rMCTRL(timer) = timer_io_channels[chan].sub_module_bits;
io_timer_set_PWM_mode(chan);
timer_set_rate(chan, 50);
}
io_timer_set_PWM_mode(timer);
timer_set_rate(timer, 50);
px4_leave_critical_section(flags);
}
@@ -873,7 +818,8 @@ uint16_t io_channel_get_ccr(unsigned channel)
return value;
}
uint32_t io_timer_get_group(unsigned timer)
// The rt has 1:1 group to channel
uint32_t io_timer_get_group(unsigned group)
{
return get_timer_channels(timer);
return get_channel_mask(group);
}
@@ -36,7 +36,7 @@ add_subdirectory(../imxrt/adc adc)
add_subdirectory(../imxrt/board_critmon board_critmon)
add_subdirectory(../imxrt/board_hw_info board_hw_info)
add_subdirectory(../imxrt/board_reset board_reset)
add_subdirectory(../imxrt/dshot dshot)
#add_subdirectory(../imxrt/dshot dshot)
add_subdirectory(../imxrt/hrt hrt)
add_subdirectory(../imxrt/led_pwm led_pwm)
add_subdirectory(../imxrt/io_pins io_pins)
@@ -41,7 +41,6 @@
#include <nuttx/irq.h>
#include <drivers/drv_hrt.h>
#include "dshot.h"
#pragma once
__BEGIN_DECLS
@@ -111,7 +110,6 @@ typedef struct timer_io_channels_t {
uint8_t sub_module; /* 0 based sub module offset */
uint8_t sub_module_bits; /* LDOK and CLDOK bits */
uint8_t timer_channel; /* Unused */
dshot_conf_t dshot;
} timer_io_channels_t;
#define SM0 0
@@ -601,16 +601,6 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t
return ret;
}
static inline constexpr timer_io_channels_t initIOTimerChannelDshot(const io_timers_t io_timers_conf[MAX_IO_TIMERS],
PWM::FlexPWMConfig pwm_config, IOMUX::Pad pad, uint32_t dshot_pinmux, uint32_t flexio_pin)
{
timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, pwm_config, pad);
ret.dshot.pinmux = dshot_pinmux;
ret.dshot.flexio_pin = flexio_pin;
return ret;
}
static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub)
{
io_timers_t ret{};
@@ -619,14 +609,3 @@ static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubm
ret.submodle = sub;
return ret;
}
static inline constexpr io_timers_t initIOPWMDshot(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub)
{
io_timers_t ret{};
ret.base = getFlexPWMBaseRegister(pwm);
ret.submodle = sub;
return ret;
}
@@ -690,16 +690,6 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t
return ret;
}
static inline constexpr timer_io_channels_t initIOTimerChannelDshot(const io_timers_t io_timers_conf[MAX_IO_TIMERS],
PWM::FlexPWMConfig pwm_config, IOMUX::Pad pad, uint32_t dshot_pinmux, uint32_t flexio_pin)
{
timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, pwm_config, pad);
ret.dshot.pinmux = dshot_pinmux;
ret.dshot.flexio_pin = flexio_pin;
return ret;
}
static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub)
{
io_timers_t ret{};
@@ -709,13 +699,14 @@ static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubm
return ret;
}
static inline constexpr io_timers_t initIOPWMDshot(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub)
static inline constexpr io_timers_t initIOPWMDshot(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub, uint32_t pinmux,
uint32_t flexio_pin)
{
io_timers_t ret{};
ret.base = getFlexPWMBaseRegister(pwm);
ret.submodle = sub;
ret.dshot.pinmux = pinmux;
ret.dshot.flexio_pin = flexio_pin;
return ret;
}
@@ -82,7 +82,7 @@ static uint8_t dshot_burst_buffer_array[DSHOT_TIMERS * DSHOT_BURST_BUFFER_SIZE(M
px4_cache_aligned_data() = {};
static uint32_t *dshot_burst_buffer[DSHOT_TIMERS] = {};
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot)
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq)
{
unsigned buffer_offset = 0;
@@ -152,22 +152,6 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bi
return ret_val == OK ? channels_init_mask : ret_val;
}
int up_bdshot_get_erpm(uint8_t channel, int *erpm)
{
// Not implemented
return -1;
}
int up_bdshot_channel_status(uint8_t channel)
{
// Not implemented
return -1;
}
void up_bdshot_status(void)
{
}
void up_dshot_trigger(void)
{
for (uint8_t timer = 0; (timer < DSHOT_TIMERS); timer++) {
-1
View File
@@ -44,7 +44,6 @@ include_directories(
add_library(px4 SHARED
${PX4_SOURCE_DIR}/platforms/qurt/unresolved_symbols.c
${PX4_SOURCE_DIR}/platforms/qurt/new_delete.cpp
${PX4_BINARY_DIR}/apps.cpp
)
-92
View File
@@ -1,92 +0,0 @@
#include <stdlib.h>
#include <new>
/*
These are the heap access function exported by the SLPI DSP image.
*/
extern "C" {
void *fc_heap_alloc(size_t size);
void fc_heap_free(void *ptr);
}
/*
Globally override new and delete so that it can use the correct
heap manager for the Qurt platform.
Note that new comes in multiple different variants. When new is used
without std::nothrow the compiler is free to assume it will not fail
as it assumes exceptions are enabled. This makes code like this
unsafe when using -fno-exceptions:
a = new b;
if (a == nullptr) {
handle_error()
}
The compiler may remove the error handling. With g++ you can use
-fcheck-new to avoid this, but on clang++ the compiler accepts
-fcheck-new as a valid flag, but doesn't implement it, and may remove
the error checking. That makes using clang++ unsafe with
-fno-exceptions if you ever call new without std::nothrow.
..It has been verified that hexagon-clang++ will remove the nullptr checks
after new if any optimization is selected for the compiler.
*/
/*
variant for new(std::nothrow), which is all that should be used in
PX4
*/
void *operator new (size_t size, std::nothrow_t const &nothrow) noexcept
{
if (size < 1) {
size = 1;
}
return (fc_heap_alloc(size));
}
void *operator new[](size_t size, std::nothrow_t const &nothrow) noexcept
{
if (size < 1) {
size = 1;
}
return (fc_heap_alloc(size));
}
/*
These variants are for new without std::nothrow. We don't want to ever
use these from PX4 code
*/
void *operator new (size_t size)
{
if (size < 1) {
size = 1;
}
return (fc_heap_alloc(size));
}
void *operator new[](size_t size)
{
if (size < 1) {
size = 1;
}
return (fc_heap_alloc(size));
}
/*
Override delete to free up memory to correct heap
*/
void operator delete (void *p) noexcept
{
if (p) { fc_heap_free(p); }
}
void operator delete[](void *ptr) noexcept
{
if (ptr) { fc_heap_free(ptr); }
}
+1 -40
View File
@@ -53,7 +53,6 @@
#include <mathlib/mathlib.h>
#include <matrix/math.hpp>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/module.h>
#include <systemlib/err.h>
#include <parameters/param.h>
@@ -925,45 +924,7 @@ CameraTrigger::status()
static int usage()
{
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
Camera trigger driver.
This module triggers cameras that are connected to the flight-controller outputs,
or simple MAVLink cameras that implement the MAVLink trigger protocol.
The driver responds to the following MAVLink trigger commands being found in missions or recieved over MAVLink:
- `MAV_CMD_DO_TRIGGER_CONTROL`
- `MAV_CMD_DO_DIGICAM_CONTROL`
- `MAV_CMD_DO_SET_CAM_TRIGG_DIST`
- `MAV_CMD_OBLIQUE_SURVEY`
The commands cause the driver to trigger camera image capture based on time or distance.
Each time an image capture is triggered, the `CAMERA_TRIGGER` MAVLink message is emitted.
A "simple MAVLink camera" is one that supports the above command set.
When configured for this kind of camera, all the driver does is emit the `CAMERA_TRIGGER` MAVLink message as expected.
The incoming commands must be forwarded to the MAVLink camera, and are automatically emitted to MAVLink channels
when found in missions.
The driver is configured using [Camera Trigger parameters](../advanced_config/parameter_reference.md#camera-trigger).
In particular:
- `TRIG_INTERFACE` - How the camera is connected to flight controller (PWM, GPIO, Seagull, MAVLink)
- `TRIG_MODE` - Distance or time based triggering, with values set by `TRIG_DISTANCE` and `TRIG_INTERVAL`.
[Setup/usage information](../camera/index.md).
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("camera_trigger", "driver");
PRINT_MODULE_USAGE_SUBCATEGORY("camera");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_COMMAND_DESCR("stop","Stop driver");
PRINT_MODULE_USAGE_COMMAND_DESCR("status","Print driver status information");
PRINT_MODULE_USAGE_COMMAND_DESCR("test","Trigger one image (not logged or forwarded to GCS)");
PRINT_MODULE_USAGE_COMMAND_DESCR("test_power","Toggle power");
PX4_INFO("usage: camera_trigger {start|stop|status|test|test_power}\n");
return 1;
}
@@ -39,7 +39,8 @@
#include <parameters/param.h>
#include <px4_platform_common/log.h>
#include <systemlib/px4_macros.h>
#define arraySize(a) (sizeof((a))/sizeof(((a)[0])))
class CameraInterface
{
@@ -75,7 +75,7 @@ SF45LaserSerial::SF45LaserSerial(const char *port, uint8_t rotation) :
// populate obstacle map members
_obstacle_map_msg.frame = obstacle_distance_s::MAV_FRAME_BODY_FRD;
_obstacle_map_msg.increment = 5;
_obstacle_map_msg.angle_offset = 2.5;
_obstacle_map_msg.angle_offset = -2.5;
_obstacle_map_msg.min_distance = UINT16_MAX;
_obstacle_map_msg.max_distance = 5000;
@@ -157,6 +157,7 @@ int SF45LaserSerial::collect()
int64_t read_elapsed = hrt_elapsed_time(&_last_read);
int ret;
/* the buffer for read chars is buflen minus null termination */
param_get(param_find("SF45_CP_LIMIT"), &_collision_constraint);
uint8_t readbuf[SF45_MAX_PAYLOAD];
float distance_m = -1.0f;
@@ -668,35 +669,34 @@ void SF45LaserSerial::sf45_process_replies(float *distance_m)
raw_yaw = raw_yaw * -1;
}
// SF45/B product guide {Data output bit: 8 Description: "Yaw angle [1/100 deg] size: int16}"
scaled_yaw = raw_yaw * SF45_SCALE_FACTOR;
switch (_yaw_cfg) {
case 0:
break;
case 1:
if (scaled_yaw > 180) {
scaled_yaw = scaled_yaw - 180;
if (raw_yaw > 180) {
raw_yaw = raw_yaw - 180;
} else {
scaled_yaw = scaled_yaw + 180; // rotation facing aft
raw_yaw = raw_yaw + 180; // rotation facing aft
}
break;
case 2:
scaled_yaw = scaled_yaw + 90; // rotation facing right
raw_yaw = raw_yaw + 90; // rotation facing right
break;
case 3:
scaled_yaw = scaled_yaw - 90; // rotation facing left
raw_yaw = raw_yaw - 90; // rotation facing left
break;
default:
break;
}
scaled_yaw = raw_yaw * SF45_SCALE_FACTOR;
// Convert to meters for rangefinder update
*distance_m = raw_distance * SF45_SCALE_FACTOR;
obstacle_dist_cm = (uint16_t)raw_distance;
+1 -25
View File
@@ -91,7 +91,7 @@ typedef enum {
* @param dshot_pwm_freq Frequency of DSHOT signal. Usually DSHOT150, DSHOT300, DSHOT600 or DSHOT1200
* @return <0 on error, the initialized channels mask.
*/
__EXPORT extern int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot);
__EXPORT extern int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq);
/**
* Set Dshot motor data, used by up_dshot_motor_data_set() and up_dshot_motor_command() (internal method)
@@ -137,28 +137,4 @@ __EXPORT extern void up_dshot_trigger(void);
*/
__EXPORT extern int up_dshot_arm(bool armed);
/**
* Print bidrectional dshot status
*/
__EXPORT extern void up_bdshot_status(void);
/**
* Get bidrectional dshot erpm for a channel
* @param channel Dshot channel
* @param erpm pointer to write the erpm value
* @return <0 on error, OK on succes
*/
__EXPORT extern int up_bdshot_get_erpm(uint8_t channel, int *erpm);
/**
* Get bidrectional dshot status for a channel
* @param channel Dshot channel
* @param erpm pointer to write the erpm value
* @return <0 on error / not supported, 0 on offline, 1 on online
*/
__EXPORT extern int up_bdshot_channel_status(uint8_t channel);
__END_DECLS
-2
View File
@@ -133,8 +133,6 @@
#define DRV_IMU_DEVTYPE_ADIS16477 0x59
#define DRV_IMU_DEVTYPE_ADIS16507 0x5A
#define DRV_IMU_DEVTYPE_SCH16T 0x5B
#define DRV_BARO_DEVTYPE_MPC2520 0x5F
#define DRV_BARO_DEVTYPE_LPS22HB 0x60
+14 -106
View File
@@ -144,9 +144,7 @@ void DShot::enable_dshot_outputs(const bool enabled)
}
}
_bidirectional_dshot_enabled = _param_bidirectional_enable.get();
int ret = up_dshot_init(_output_mask, dshot_frequency, _bidirectional_dshot_enabled);
int ret = up_dshot_init(_output_mask, dshot_frequency);
if (ret < 0) {
PX4_ERR("up_dshot_init failed (%i)", ret);
@@ -159,7 +157,6 @@ void DShot::enable_dshot_outputs(const bool enabled)
for (unsigned i = 0; i < _num_outputs; ++i) {
if (((1 << i) & _output_mask) == 0) {
_mixing_output.disableFunction(i);
}
}
@@ -170,10 +167,6 @@ void DShot::enable_dshot_outputs(const bool enabled)
}
_outputs_initialized = true;
if (_bidirectional_dshot_enabled) {
init_telemetry(NULL);
}
}
if (_outputs_initialized) {
@@ -213,20 +206,17 @@ void DShot::init_telemetry(const char *device)
_telemetry->esc_status_pub.advertise();
if (device != NULL) {
int ret = _telemetry->handler.init(device);
int ret = _telemetry->handler.init(device);
if (ret != 0) {
PX4_ERR("telemetry init failed (%i)", ret);
}
if (ret != 0) {
PX4_ERR("telemetry init failed (%i)", ret);
}
update_telemetry_num_motors();
}
int DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data)
void DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data)
{
int ret = 0;
// fill in new motor data
esc_status_s &esc_status = _telemetry->esc_status_pub.get();
@@ -249,83 +239,18 @@ int DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelem
esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_DSHOT;
esc_status.esc_count = _telemetry->handler.numMotors();
++esc_status.counter;
// FIXME: mark all ESC's as online, otherwise commander complains even for a single dropout
esc_status.esc_online_flags = (1 << esc_status.esc_count) - 1;
esc_status.esc_armed_flags = (1 << esc_status.esc_count) - 1;
ret = 1; // Indicate we wrapped, so we publish data
_telemetry->esc_status_pub.update();
// reset esc data (in case a motor times out, so we won't send stale data)
memset(&esc_status.esc, 0, sizeof(_telemetry->esc_status_pub.get().esc));
esc_status.esc_online_flags = 0;
}
_telemetry->last_telemetry_index = telemetry_index;
return ret;
}
void DShot::publish_esc_status(void)
{
esc_status_s &esc_status = _telemetry->esc_status_pub.get();
int telemetry_index = 0;
// clear data of the esc that are offline
for (int index = 0; (index < _telemetry->last_telemetry_index); index++) {
if ((esc_status.esc_online_flags & (1 << index)) == 0) {
memset(&esc_status.esc[index], 0, sizeof(struct esc_report_s));
}
}
// FIXME: mark all UART Telemetry ESC's as online, otherwise commander complains even for a single dropout
esc_status.esc_count = _telemetry->handler.numMotors();
esc_status.esc_online_flags = (1 << esc_status.esc_count) - 1;
esc_status.esc_armed_flags = (1 << esc_status.esc_count) - 1;
if (_bidirectional_dshot_enabled) {
for (unsigned i = 0; i < _num_outputs; i++) {
if (_mixing_output.isFunctionSet(i)) {
if (up_bdshot_channel_status(i)) {
esc_status.esc_online_flags |= 1 << i;
} else {
esc_status.esc_online_flags &= ~(1 << i);
}
++telemetry_index;
}
}
}
// ESC telem wrap around or bdshot update
_telemetry->esc_status_pub.update();
// reset esc online flags
esc_status.esc_online_flags = 0;
}
int DShot::handle_new_bdshot_erpm(void)
{
int num_erpms = 0;
int telemetry_index = 0;
int erpm;
esc_status_s &esc_status = _telemetry->esc_status_pub.get();
esc_status.timestamp = hrt_absolute_time();
esc_status.counter = _esc_status_counter++;
esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_DSHOT;
esc_status.esc_armed_flags = _outputs_on;
for (unsigned i = 0; i < _num_outputs; i++) {
if (_mixing_output.isFunctionSet(i)) {
if (up_bdshot_get_erpm(i, &erpm) == 0) {
num_erpms++;
esc_status.esc_online_flags |= 1 << telemetry_index;
esc_status.esc[telemetry_index].timestamp = hrt_absolute_time();
esc_status.esc[telemetry_index].esc_rpm = (erpm * 100) / (_param_mot_pole_count.get() / 2);
esc_status.esc[telemetry_index].actuator_function = _telemetry->actuator_functions[telemetry_index];
}
++telemetry_index;
}
}
return num_erpms;
}
int DShot::send_command_thread_safe(const dshot_command_t command, const int num_repetitions, const int motor_index)
@@ -538,7 +463,6 @@ void DShot::Run()
if (_telemetry) {
int telem_update = _telemetry->handler.update();
int need_to_publish = 0;
// Are we waiting for ESC info?
if (_waiting_for_esc_info) {
@@ -548,21 +472,10 @@ void DShot::Run()
}
} else if (telem_update >= 0) {
need_to_publish = handle_new_telemetry_data(telem_update, _telemetry->handler.latestESCData());
}
if (_bidirectional_dshot_enabled) {
// Add bdshot data to esc status
need_to_publish += handle_new_bdshot_erpm();
}
if (need_to_publish > 0) {
// ESC telem wrap around or bdshot update
publish_esc_status();
handle_new_telemetry_data(telem_update, _telemetry->handler.latestESCData());
}
}
if (_parameter_update_sub.updated()) {
update_params();
}
@@ -800,11 +713,6 @@ int DShot::print_status()
_telemetry->handler.printStatus();
}
/* Print dshot status */
if (_bidirectional_dshot_enabled) {
up_bdshot_status();
}
return 0;
}
+2 -9
View File
@@ -131,11 +131,7 @@ private:
void init_telemetry(const char *device);
int handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data);
void publish_esc_status(void);
int handle_new_bdshot_erpm(void);
void handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data);
int request_esc_info();
@@ -162,7 +158,6 @@ private:
bool _outputs_initialized{false};
bool _outputs_on{false};
bool _waiting_for_esc_info{false};
bool _bidirectional_dshot_enabled{false};
static constexpr unsigned _num_outputs{DIRECT_PWM_OUTPUT_CHANNELS};
uint32_t _output_mask{0};
@@ -174,14 +169,12 @@ private:
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)};
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
uint16_t _esc_status_counter{0};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::DSHOT_MIN>) _param_dshot_min,
(ParamBool<px4::params::DSHOT_3D_ENABLE>) _param_dshot_3d_enable,
(ParamInt<px4::params::DSHOT_3D_DEAD_H>) _param_dshot_3d_dead_h,
(ParamInt<px4::params::DSHOT_3D_DEAD_L>) _param_dshot_3d_dead_l,
(ParamInt<px4::params::MOT_POLE_COUNT>) _param_mot_pole_count,
(ParamBool<px4::params::DSHOT_BIDIR_EN>) _param_bidirectional_enable
(ParamInt<px4::params::MOT_POLE_COUNT>) _param_mot_pole_count
)
};
-4
View File
@@ -183,9 +183,6 @@ bool DShotTelemetry::decodeByte(uint8_t byte, bool &successful_decoding)
_latest_data.erpm);
++_num_successful_responses;
successful_decoding = true;
} else {
++_num_checksum_errors;
}
return true;
@@ -198,7 +195,6 @@ void DShotTelemetry::printStatus() const
{
PX4_INFO("Number of successful ESC frames: %i", _num_successful_responses);
PX4_INFO("Number of timeouts: %i", _num_timeouts);
PX4_INFO("Number of CRC errors: %i", _num_checksum_errors);
}
uint8_t DShotTelemetry::updateCrc8(uint8_t crc, uint8_t crc_seed)
-1
View File
@@ -140,5 +140,4 @@ private:
// statistics
int _num_timeouts{0};
int _num_successful_responses{0};
int _num_checksum_errors{0};
};
-10
View File
@@ -33,16 +33,6 @@ parameters:
When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent.
type: boolean
default: 0
DSHOT_BIDIR_EN:
description:
short: Enable bidirectional DShot
long: |
This parameter enables bidirectional DShot which provides RPM feedback.
Note that this requires ESCs that support bidirectional DSHot, e.g. BlHeli32.
This is not the same as DShot telemetry which requires an additional serial connection.
type: boolean
default: 0
reboot_required: true
DSHOT_3D_DEAD_H:
description:
short: DSHOT 3D deadband high
+7 -19
View File
@@ -728,8 +728,7 @@ GPS::run()
int32_t gps_ubx_mode = 0;
param_get(handle, &gps_ubx_mode);
switch (gps_ubx_mode) {
case 1: // heading
if (gps_ubx_mode == 1) { // heading
if (_instance == Instance::Main) {
ubx_mode = GPSDriverUBX::UBXMode::RoverWithMovingBase;
@@ -737,13 +736,10 @@ GPS::run()
ubx_mode = GPSDriverUBX::UBXMode::MovingBase;
}
break;
case 2:
} else if (gps_ubx_mode == 2) {
ubx_mode = GPSDriverUBX::UBXMode::MovingBase;
break;
case 3:
} else if (gps_ubx_mode == 3) {
if (_instance == Instance::Main) {
ubx_mode = GPSDriverUBX::UBXMode::RoverWithMovingBaseUART1;
@@ -751,18 +747,11 @@ GPS::run()
ubx_mode = GPSDriverUBX::UBXMode::MovingBaseUART1;
}
break;
case 4:
} else if (gps_ubx_mode == 4) {
ubx_mode = GPSDriverUBX::UBXMode::MovingBaseUART1;
break;
case 5: // rover with static base on Uart2
} else if (gps_ubx_mode == 5) { // rover with static base on Uart2
ubx_mode = GPSDriverUBX::UBXMode::RoverWithStaticBaseUart2;
break;
default:
break;
}
}
@@ -950,8 +939,7 @@ GPS::run()
set_device_type(DRV_GPS_DEVTYPE_UBX_9);
break;
case GPSDriverUBX::Board::u_blox9_F9P_L1L2:
case GPSDriverUBX::Board::u_blox9_F9P_L1L5:
case GPSDriverUBX::Board::u_blox9_F9P:
set_device_type(DRV_GPS_DEVTYPE_UBX_F9P);
break;
@@ -1572,4 +1560,4 @@ int
gps_main(int argc, char *argv[])
{
return GPS::main(argc, argv);
}
}
+5 -10
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2016-2024 PX4 Development Team. All rights reserved.
* Copyright (c) 2016 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
@@ -152,9 +152,8 @@ PARAM_DEFINE_INT32(GPS_UBX_CFG_INTF, 0);
*
* The offset angle increases clockwise.
*
* Set this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux)
* antenna is placed on the right side of the vehicle and the moving base
* antenna is on the left side.
* Set this to 90 if the rover (or Unicore primary) antenna is placed on the
* right side of the vehicle and the moving base antenna is on the left side.
*
* (Note: the Unicore primary antenna is the one connected on the right as seen
* from the top).
@@ -248,16 +247,14 @@ PARAM_DEFINE_INT32(GPS_2_PROTOCOL, 1);
* 2 : Use Galileo
* 3 : Use BeiDou
* 4 : Use GLONASS
* 5 : Use NAVIC
*
* @min 0
* @max 63
* @max 31
* @bit 0 GPS (with QZSS)
* @bit 1 SBAS
* @bit 2 Galileo
* @bit 3 BeiDou
* @bit 4 GLONASS
* @bit 5 NAVIC
*
* @reboot_required true
* @group GPS
@@ -280,16 +277,14 @@ PARAM_DEFINE_INT32(GPS_1_GNSS, 0);
* 2 : Use Galileo
* 3 : Use BeiDou
* 4 : Use GLONASS
* 5 : Use NAVIC
*
* @min 0
* @max 63
* @max 31
* @bit 0 GPS (with QZSS)
* @bit 1 SBAS
* @bit 2 Galileo
* @bit 3 BeiDou
* @bit 4 GLONASS
* @bit 5 NAVIC
*
* @reboot_required true
* @group GPS
-1
View File
@@ -8,7 +8,6 @@ menu "IMU"
select DRIVERS_IMU_ANALOG_DEVICES_ADIS16470
select DRIVERS_IMU_BOSCH_BMI055
select DRIVERS_IMU_BOSCH_BMI088
select DRIVERS_IMU_MURATA_SCH16T
select DRIVERS_IMU_NXP_FXAS21002C
select DRIVERS_IMU_NXP_FXOS8701CQ
select DRIVERS_IMU_INVENSENSE_ICM20602
@@ -172,9 +172,7 @@ void ADIS16507::RunImpl()
const uint16_t DIAG_STAT = RegisterRead(Register::DIAG_STAT);
if (DIAG_STAT != 0) {
PX4_ERR("self test failed, resetting. DIAG_STAT: %#X", DIAG_STAT);
_state = STATE::RESET;
ScheduleDelayed(3_s);
PX4_ERR("DIAG_STAT: %#X", DIAG_STAT);
} else {
PX4_DEBUG("self test passed");

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