Compare commits

..

4 Commits

Author SHA1 Message Date
Daniel Agar c11f61d57d commander: skip estimatorCheck for now 2024-02-15 15:46:31 -05:00
Daniel Agar d9a924225c simulator_mavlink: add heading_good_for_control 2024-02-15 15:46:14 -05:00
Daniel Agar 5f91c7fc2b simulation: HIL_STATE_QUATERNION add angular acceleration and protect from initial lat/lon 0 2024-02-15 15:20:33 -05:00
Daniel Agar 79538ac013 [WIP] simple simulation without sensor/estimator 2024-02-15 14:57:37 -05:00
452 changed files with 7355 additions and 18327 deletions
+1 -1
View File
@@ -120,7 +120,7 @@ pipeline {
"px4_fmu-v6xrt_rover",
"px4_io-v2_default",
"raspberrypi_pico_default",
"siyi_n7_default",
"siyi_n7_default"
"sky-drones_smartap-airlink_default",
"spracing_h7extreme_default",
"thepeach_k1_default",
-14
View File
@@ -1,14 +0,0 @@
root = true
[*]
insert_final_newline = false
[{*.{c,cpp,cc,h,hpp},CMakeLists.txt,Kconfig}]
indent_style = tab
tab_width = 8
# Not in the official standard, but supported by many editors
max_line_length = 120
[*.yaml]
indent_style = space
indent_size = 2
+1 -1
View File
@@ -81,5 +81,5 @@
url = https://github.com/PX4/PX4-gazebo-models.git
branch = main
[submodule "boards/modalai/voxl2/libfc-sensor-api"]
path = boards/modalai/voxl2/libfc-sensor-api
path = src/modules/muorb/apps/libfc-sensor-api
url = https://gitlab.com/voxl-public/voxl-sdk/core-libs/libfc-sensor-api.git
Vendored
+2 -4
View File
@@ -171,11 +171,9 @@ pipeline {
sh('cp airframes.md PX4-user_guide/en/airframes/airframe_reference.md')
sh('cp parameters.md PX4-user_guide/en/advanced_config/parameter_reference.md')
sh('cp -R modules/*.md PX4-user_guide/en/modules/')
sh('cp -R graph_*.json PX4-user_guide/.vuepress/public/en/middleware/') // vuepress
sh('cp -R graph_*.json PX4-user_guide/public/middleware/') // vitepress
sh('cp -R graph_*.json PX4-user_guide/.vuepress/public/en/middleware/')
sh('cp -R msg_docs/*.md PX4-user_guide/en/msg_docs/')
sh('cp -R failsafe_sim/* PX4-user_guide/.vuepress/public/en/config/failsafe') // vuepress
sh('cp -R failsafe_sim/* PX4-user_guide/public/config/failsafe') // vitepress
sh('cp -R failsafe_sim/* PX4-user_guide/.vuepress/public/en/config/failsafe')
sh('cd PX4-user_guide; git status; git add .; git commit -a -m "Update PX4 Firmware metadata `date`" || true')
sh('cd PX4-user_guide; git push origin main || true')
sh('rm -rf PX4-user_guide')
@@ -1,80 +0,0 @@
#!/bin/sh
# @name Gazebo lawnmower
# @type Rover
# @class Rover
. ${R}etc/init.d/rc.rover_differential_defaults
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=lawnmower}
param set-default SIM_GZ_EN 1 # Gazebo bridge
# Simulated sensors
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1
# We can arm and drive in manual mode when it slides and GPS check fails:
param set-default COM_ARM_WO_GPS 1
# Set Differential Drive Kinematics Library parameters:
param set RDD_WHEEL_BASE 0.9
param set RDD_WHEEL_RADIUS 0.22
param set RDD_WHEEL_SPEED 10.0 # Maximum wheel speed rad/s, approx 8 km/h
# Actuator mapping - set SITL motors/servos output parameters:
# "Motors" - motor channels 0 (Right) and 1 (Left) - via Wheels GZ bridge:
param set-default SIM_GZ_WH_FUNC1 101 # right wheel
#param set-default SIM_GZ_WH_MIN1 0
#param set-default SIM_GZ_WH_MAX1 200
#param set-default SIM_GZ_WH_DIS1 100
#param set-default SIM_GZ_WH_FAIL1 100
param set-default SIM_GZ_WH_FUNC2 102 # left wheel
#param set-default SIM_GZ_WH_MIN2 0
#param set-default SIM_GZ_WH_MAX2 200
#aram set-default SIM_GZ_WH_DIS2 100
#param set-default SIM_GZ_WH_FAIL2 100
param set-default SIM_GZ_WH_REV 0 # no need to reverse any wheels
# Note: The servo configurations ( SIM_GZ_SV_FUNC*) outlined below are intended for educational purposes in this simulation.
# They do not have physical effects in the simulated environment, except for actuating the joints. Their definitions are meant to demonstrate
# how actuators could be mapped and configured in a real-world application, providing a foundation for understanding and implementing actuator
# controls in practical scenarios.
# Cutter deck blades clutch, PCA9685 servo channel 3, "RC FLAPS" (406) - leftmost switch, or "Servo 3" (203):
param set-default SIM_GZ_SV_FUNC3 203
param set-default SIM_GZ_SV_MIN3 0
param set-default SIM_GZ_SV_MAX3 1000
param set-default SIM_GZ_SV_DIS3 500
param set-default SIM_GZ_SV_FAIL3 500
# Gas engine throttle, PCA9685 servo channel 4, "RC AUX1" (407) - left knob, or "Servo 4" (204):
# - on minimum when disarmed or failed:
param set-default SIM_GZ_SV_FUNC4 204
param set-default SIM_GZ_SV_MIN4 0
param set-default SIM_GZ_SV_MAX4 1000
param set-default SIM_GZ_SV_DIS4 500
param set-default SIM_GZ_SV_FAIL4 500
# Controlling PCA9685 servos 5,6,7,8 directly via "Servo 5..8" setting, by publishing actuator_servos.control[]:
# Strobes, PCA9685 servo channel 5, "Servo 5" (205) - flashing indicates Mission mode:
#param set-default SIM_GZ_SV_FUNC5 205
#param set-default SIM_GZ_SV_MIN5 1000
#param set-default SIM_GZ_SV_MAX5 2000
#param set-default SIM_GZ_SV_DIS5 1000
#param set-default SIM_GZ_SV_FAIL5 1000
# Horn, PCA9685 servo channel 6, "Servo 6" (206) - for alarms like GPS failure:
#param set-default SIM_GZ_SV_FUNC6 206
# Spare PCA9685 servo channel 7 on "RC AUX2" (408) - right knob, or "Servo 7" (207):
#param set-default SIM_GZ_SV_FUNC7 207
# Spare PCA9685 servo channel 8 - "Servo 8" (208):
#param set-default SIM_GZ_SV_FUNC8 208
@@ -82,7 +82,6 @@ px4_add_romfs_files(
4008_gz_advanced_plane
4009_gz_r1_rover
4010_gz_x500_mono_cam
4011_gz_lawnmower
6011_gazebo-classic_typhoon_h480
6011_gazebo-classic_typhoon_h480.post
+1 -1
View File
@@ -253,7 +253,7 @@ fi
tone_alarm start
rc_update start
manual_control start
sensors start
#sensors start
commander start
if ! pwm_out_sim start -m sim
+21 -72
View File
@@ -34,79 +34,28 @@
add_subdirectory(airframes)
px4_add_romfs_files(
rc.airship_apps
rc.airship_defaults
rc.autostart_ext
rcS
rc.sensors
rc.vehicle_setup
# TODO
rc.balloon_apps
rc.balloon_defaults
rc.boat_defaults
rc.fw_apps
rc.fw_defaults
rc.heli_defaults
rc.logging
rc.mc_apps
rc.mc_defaults
rcS
rc.sensors
rc.thermal_cal
rc.rover_apps
rc.rover_defaults
rc.rover_differential_apps
rc.rover_differential_defaults
rc.uuv_apps
rc.uuv_defaults
rc.vehicle_setup
rc.vtol_apps
rc.vtol_defaults
)
if(CONFIG_MODULES_AIRSHIP_ATT_CONTROL)
px4_add_romfs_files(
rc.airship_apps
rc.airship_defaults
)
endif()
if(CONFIG_MODULES_FW_RATE_CONTROL)
px4_add_romfs_files(
rc.fw_apps
rc.fw_defaults
)
endif()
if(CONFIG_MODULES_MC_RATE_CONTROL)
px4_add_romfs_files(
rc.heli_defaults
rc.mc_apps
rc.mc_defaults
)
endif()
if(CONFIG_MODULES_ROVER_POS_CONTROL)
px4_add_romfs_files(
rc.rover_apps
rc.rover_defaults
rc.boat_defaults # hack
)
endif()
if(CONFIG_MODULES_DIFFERENTIAL_DRIVE)
px4_add_romfs_files(
rc.rover_differential_apps
rc.rover_differential_defaults
)
endif()
if(CONFIG_MODULES_UUV_ATT_CONTROL)
px4_add_romfs_files(
rc.uuv_apps
rc.uuv_defaults
)
endif()
if(CONFIG_MODULES_VTOL_ATT_CONTROL)
px4_add_romfs_files(
rc.vtol_apps
rc.vtol_defaults
)
endif()
if(CONFIG_MODULES_LOGGER)
px4_add_romfs_files(
rc.logging
)
endif()
if(CONFIG_MODULES_TEMPERATURE_COMPENSATION)
px4_add_romfs_files(
rc.thermal_cal
)
endif()
@@ -32,127 +32,94 @@
############################################################################
px4_add_romfs_files(
# [0-999] Reserved (historical)
# [0-999] Reserved (historical)"
# [1000, 1999] Simulation setups"
1001_rc_quad_x.hil
1002_standard_vtol.hil
1100_rc_quad_x_sih.hil
1101_rc_plane_sih.hil
1102_tailsitter_duo_sih.hil
# [2000, 2999] Standard planes"
2100_standard_plane
2106_albatross
2507_cloudship
# [3000, 3999] Flying wing"
3000_generic_wing
# [4000, 4999] Quadrotor x"
4001_quad_x
4014_s500
4015_holybro_s500
4016_holybro_px4vision
4017_nxp_hovergames
4019_x500_v2
4020_holybro_px4vision_v1_5
4041_beta75x
4050_generic_250
4052_holybro_qav250
4053_holybro_kopis2
4061_atl_mantis_edu
4071_ifo
4073_ifo-s
4500_clover4
4901_crazyflie21
# [5000, 5999] Quadrotor +"
5001_quad_+
# [6000, 6999] Hexarotor x"
6001_hexa_x
6002_draco_r
# [7000, 7999] Hexarotor +"
7001_hexa_+
# [8000, 8999] Octorotor +"
8001_octo_x
# [9000, 9999] Octorotor +"
9001_octo_+
# [11000, 11999] Hexa Cox
11001_hexa_cox
# [12000, 12999] Octo Cox
12001_octo_cox
# [13000, 13999] VTOL
13000_generic_vtol_standard
13100_generic_vtol_tiltrotor
13013_deltaquad
13014_vtol_babyshark
13030_generic_vtol_quad_tiltrotor
13200_generic_vtol_tailsitter
# [14000, 14999] MC with tilt
14001_generic_mc_with_tilt
16001_helicopter
# [17000, 17999] Autogyro
17002_TF-AutoG2
17003_TF-G2
# [18000, 18999] High-altitude balloons
18001_TF-B1
# [22000, 22999] Reserve for custom models
24001_dodeca_cox
50000_generic_ground_vehicle
50004_nxpcup_car_dfrobot_gpx
50003_aion_robotics_r1_rover
# [60000, 61000] (Unmanned) Underwater Robots
60000_uuv_generic
60001_uuv_hippocampus
60002_uuv_bluerov2_heavy
)
if(CONFIG_MODULES_SIMULATION_PWM_OUT_SIM)
px4_add_romfs_files(
# [1000, 1999] Simulation setups
1001_rc_quad_x.hil
1002_standard_vtol.hil
1100_rc_quad_x_sih.hil
1101_rc_plane_sih.hil
1102_tailsitter_duo_sih.hil
)
endif()
if(CONFIG_MODULES_MC_RATE_CONTROL)
px4_add_romfs_files(
# [4000, 4999] Quadrotor x
4001_quad_x
4014_s500
4015_holybro_s500
4016_holybro_px4vision
4017_nxp_hovergames
4019_x500_v2
4020_holybro_px4vision_v1_5
4041_beta75x
4050_generic_250
4052_holybro_qav250
4053_holybro_kopis2
4061_atl_mantis_edu
4071_ifo
4073_ifo-s
4500_clover4
4901_crazyflie21
# [5000, 5999] Quadrotor +
5001_quad_+
# [6000, 6999] Hexarotor x
6001_hexa_x
6002_draco_r
# [7000, 7999] Hexarotor +
7001_hexa_+
# [8000, 8999] Octorotor +
8001_octo_x
# [9000, 9999] Octorotor +
9001_octo_+
# [11000, 11999] Hexa Cox
11001_hexa_cox
# [12000, 12999] Octo Cox
12001_octo_cox
# [14000, 14999] MC with tilt
14001_generic_mc_with_tilt
16001_helicopter
24001_dodeca_cox
)
endif()
if(CONFIG_MODULES_FW_RATE_CONTROL)
px4_add_romfs_files(
# [2000, 2999] Standard planes
2100_standard_plane
2106_albatross
# [3000, 3999] Flying wing
3000_generic_wing
# [17000, 17999] Autogyro
17002_TF-AutoG2
17003_TF-G2
)
endif()
if(CONFIG_MODULES_AIRSHIP_ATT_CONTROL)
px4_add_romfs_files(
2507_cloudship
)
endif()
if(CONFIG_MODULES_VTOL_ATT_CONTROL)
px4_add_romfs_files(
# [13000, 13999] VTOL
13000_generic_vtol_standard
13100_generic_vtol_tiltrotor
13013_deltaquad
13014_vtol_babyshark
13030_generic_vtol_quad_tiltrotor
13200_generic_vtol_tailsitter
)
endif()
if(CONFIG_MODULES_ROVER_POS_CONTROL)
px4_add_romfs_files(
50000_generic_ground_vehicle
50004_nxpcup_car_dfrobot_gpx
)
endif()
if(CONFIG_MODULES_DIFFERENTIAL_DRIVE)
px4_add_romfs_files(
50003_aion_robotics_r1_rover
)
endif()
if(CONFIG_MODULES_UUV_ATT_CONTROL)
px4_add_romfs_files(
# [60000, 61000] (Unmanned) Underwater Robots
60000_uuv_generic
60001_uuv_hippocampus
60002_uuv_bluerov2_heavy
)
endif()
@@ -28,6 +28,7 @@ param set-default EKF2_ARSP_THR 8
param set-default EKF2_FUSE_BETA 1
param set-default EKF2_GPS_CHECK 21
param set-default EKF2_MAG_ACCLIM 0
param set-default EKF2_MAG_YAWLIM 0
param set-default EKF2_REQ_EPH 10
param set-default EKF2_REQ_EPV 10
param set-default EKF2_REQ_HDRIFT 0.5
+2 -12
View File
@@ -439,12 +439,7 @@ else
#
# Start a thermal calibration if required.
#
set RC_THERMAL_CAL ${R}etc/init.d/rc.thermal_cal
if [ -f ${RC_THERMAL_CAL} ]
then
. ${RC_THERMAL_CAL}
fi
unset RC_THERMAL_CAL
. ${R}etc/init.d/rc.thermal_cal
#
# Start gimbal to control mounts such as gimbals, disabled by default.
@@ -505,12 +500,7 @@ else
#
# Start the logger.
#
set RC_LOGGING ${R}etc/init.d/rc.logging
if [ -f ${RC_LOGGING} ]
then
. ${RC_LOGGING}
fi
unset RC_LOGGING
. ${R}etc/init.d/rc.logging
#
# Set additional parameters and env variables for selected AUTOSTART.
@@ -30,5 +30,4 @@ exec find boards msg src platforms test \
-path src/lib/cdrstream/cyclonedds -prune -o \
-path src/lib/cdrstream/rosidl -prune -o \
-path src/modules/zenoh/zenoh-pico -prune -o \
-path boards/modalai/voxl2/libfc-sensor-api -prune -o \
-type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) | grep $PATTERN
-126
View File
@@ -1,126 +0,0 @@
#!/usr/bin/env python3
# Copyright (c) 2018-2019, Ulf Magnusson
# SPDX-License-Identifier: ISC
"""
Writes a configuration file where as many symbols as possible are set to 'y'.
The default output filename is '.config'. A different filename can be passed
in the KCONFIG_CONFIG environment variable.
Usage for the Linux kernel:
$ make [ARCH=<arch>] scriptconfig SCRIPT=Kconfiglib/allyesconfig.py
"""
import kconfiglib
import os
exception_list = [
'DRIVERS_BOOTLOADERS', # Only used for bootloader target
'MODULES_PX4IOFIRMWARE', # Only needed for PX4IO firmware itself, maybe fix through dependencies
'BOARD_LTO', # Experimental
'BOARD_TESTING', # Don't build test suite
'BOARD_CONSTRAINED_FLASH', # only used to reduce flash size
'BOARD_NO_HELP', # only used to reduce flash size
'BOARD_CONSTRAINED_MEMORY', # only used to reduce flash size
'BOARD_EXTERNAL_METADATA', # only used to reduce flash size
'BOARD_CRYPTO', # Specialized use
'BOARD_PROTECTED', # Experimental for MPU use
'DRIVERS_LIGHTS_RGBLED_PWM', # Only on specific boards, needs dependency fixing
'DRIVERS_LIGHTS_NEOPIXEL', # Only on specific boards, needs dependency fixing
'DRIVERS_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL', # Only on specific boards, needs dependency fixing
'PARAM_PRIMARY', # Plainly broken
'PARAM_REMOTE', # Plainly broken
'DRIVERS_ACTUATORS_VOXL_ESC', # Dependency need fixing, requires VOXL_ESC_DEFAULT_XXX
'DRIVERS_VOXL2_IO', # Dependency need fixing, requires VOXL2_IO_DEFAULT_XX
'DRIVERS_BAROMETER_TCBP001TA', # Requires hardcoded PX4_SPI_BUS_BARO mapping
'DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50', # Requires hardcoded PX4_SPI_BUS_BARO mapping
'DRIVERS_DISTANCE_SENSOR_SRF05', # Requires hardcoded GPIO_ULTRASOUND
'DRIVERS_PPS_CAPTURE', # Requires PPS GPIO config
'DRIVERS_PWM_INPUT', # Requires PWM config
'DRIVERS_TEST_PPM', # PIN config not portable
'DRIVERS_TATTU_CAN', # Broken needs fixing
'MODULES_REPLAY', # Fails on NuttX targets maybe force POSIX dependency?
'SYSTEMCMDS_HIST', # This module can only be used on boards that enable BOARD_ENABLE_LOG_HISTORY
'SYSTEMCMDS_GPIO', # PIN config not portable
'SYSTEMCMDS_SHUTDOWN', # Needs dependency checking
'EXAMPLES_DYN_HELLO', # NuttX doesn't support dynamic linking
'SYSTEMCMDS_DYN', # NuttX doesn't support dynamic linking
'DRIVERS_RPI_RC_IN', # RPI specific driver
'SYSTEMCMDS_I2C_LAUNCHER', # undefined reference to `system',
'MODULES_MUORB_APPS', # Weird QURT/Posix package doesn't work on x86 px4 sitl
'MODULES_SIMULATION_SIMULATOR_SIH', # Causes compile errors
]
exception_list_sitl = [
'DRIVERS_BAROMETER', # Fails I2C dependencies
'COMMON_BAROMETERS', # Fails I2C dependencies
'DRIVERS_ADC_BOARD_ADC', # Fails HW dependencies, I think this only works on NuttX
'DRIVERS_CAMERA_CAPTURE', # GPIO config failure
'DRIVERS_DSHOT', # No Posix driver, I think this only works on NuttX
'DRIVERS_PWM_OUT', # No Posix driver, I think this only works on NuttX
'COMMON', # Fails I2C dependencies
'DRIVERS', # Fails I2C dependencies
'SYSTEMCMDS_REBOOT', # Sitl can't reboot
'MODULES_BATTERY_STATUS', # Sitl doesn't provide a power brick
'SYSTEMCMDS_SERIAL_PASSTHRU', # Not supported in SITL
'SYSTEMCMDS_SERIAL_TEST', # Not supported in SITL
'SYSTEMCMDS_SD_STRESS', # Not supported in SITL
'SYSTEMCMDS_SD_BENCH', # Not supported in SITL
'SYSTEMCMDS_I2CDETECT', # Not supported in SITL
'SYSTEMCMDS_DMESG', # Not supported in SITL
'SYSTEMCMDS_USB_CONNECTED', # Not supported in SITL
]
def main():
kconf = kconfiglib.standard_kconfig(__doc__)
if 'BASE_DEFCONFIG' in os.environ:
kconf.load_config(os.environ['BASE_DEFCONFIG'])
if 'MODEL' in os.environ:
if os.environ['MODEL'] == 'sitl':
for sym in kconf.unique_defined_syms:
if sym.name.startswith(tuple(exception_list_sitl)):
exception_list.append(sym.name)
# See allnoconfig.py
kconf.warn = False
# Try to set all symbols to 'y'. Dependencies might truncate the value down
# later, but this will at least give the highest possible value.
#
# Assigning 0/1/2 to non-bool/tristate symbols has no effect (int/hex
# symbols still take a string, because they preserve formatting).
for sym in kconf.unique_defined_syms:
# Set choice symbols to 'm'. This value will be ignored for choices in
# 'y' mode (the "normal" mode), which will instead just get their
# default selection, but will set all symbols in m-mode choices to 'm',
# which is as high as they can go.
#
# Here's a convoluted example of how you might get an m-mode choice
# even during allyesconfig:
#
# choice
# tristate "weird choice"
# depends on m
if sym.name not in exception_list:
sym.set_value(1 if sym.choice else 2)
# Set all choices to the highest possible mode
for choice in kconf.unique_choices:
choice.set_value(2)
kconf.warn = True
kconf.load_allconfig("allyes.config")
print(kconf.write_config())
if __name__ == "__main__":
main()
+1 -8
View File
@@ -73,16 +73,9 @@ struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path)
#include <lib/matrix/matrix/math.hpp>
#include <lib/mathlib/mathlib.h>
@{
queue_length = 1
for constant in spec.constants:
if constant.name == 'ORB_QUEUE_LENGTH':
queue_length = constant.val
}@
@[for topic in topics]@
static_assert(static_cast<orb_id_size_t>(ORB_ID::@topic) == @(all_topics.index(topic)), "ORB_ID index mismatch");
ORB_DEFINE(@topic, struct @uorb_struct, @(struct_size-padding_end_size), @(message_hash)u, static_cast<orb_id_size_t>(ORB_ID::@topic), @queue_length);
ORB_DEFINE(@topic, struct @uorb_struct, @(struct_size-padding_end_size), @(message_hash)u, static_cast<orb_id_size_t>(ORB_ID::@topic));
@[end for]
void print_message(const orb_metadata *meta, const @uorb_struct& message)
+1 -1
View File
@@ -4,7 +4,7 @@
"description": "Firmware for the ARK flow board",
"image": "",
"build_time": 0,
"summary": "ARKFLOW",
"summary": "ARFFLOW",
"version": "0.1",
"image_size": 0,
"image_maxsize": 2080768,
Binary file not shown.
@@ -20,7 +20,6 @@ CONFIG_UAVCANNODE_RTK_DATA=y
CONFIG_UAVCANNODE_SAFETY_BUTTON=y
CONFIG_UAVCANNODE_STATIC_PRESSURE=y
CONFIG_UAVCANNODE_STATIC_TEMPERATURE=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_SENSORS=y
@@ -11,5 +11,3 @@ param set-default SENS_IMU_CLPNOTI 0
safety_button start
tone_alarm start
ekf2 start
@@ -50,7 +50,6 @@ CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_DISABLE_BUFFERING=y
CONFIG_STM32_FLASH_CONFIG_G=y
CONFIG_STM32_NOEXT_VECTORS=y
CONFIG_STM32_TIM8=y
CONFIG_TASK_NAME_SIZE=0
@@ -123,7 +123,6 @@ CONFIG_STM32_ADC1=y
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
CONFIG_STM32_DMA1=y
CONFIG_STM32_DMA2=y
CONFIG_STM32_FLASH_CONFIG_G=y
CONFIG_STM32_FLASH_PREFETCH=y
CONFIG_STM32_FLOWCONTROL_BROKEN=y
CONFIG_STM32_I2C1=y
@@ -33,7 +33,7 @@
*
****************************************************************************/
/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and
/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
* 256Kb of SRAM. SRAM is split up into three blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
@@ -33,7 +33,7 @@
*
****************************************************************************/
/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and
/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
* 256Kb of SRAM. SRAM is split up into three blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
+3
View File
@@ -64,6 +64,9 @@
// Hacks for MAVLink RC button input
#define ATL_MANTIS_RC_INPUT_HACKS
// Hacks for MAVLink RC button input
#define ATL_MANTIS_RC_INPUT_HACKS
/*
* ADC channels
*
@@ -74,7 +74,8 @@
#define ADC_BATTERY_CURRENT_CHANNEL 13
#define ADC_RC_RSSI_CHANNEL 12
/* Define Battery Voltage Divider and A per V */
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (11.12f)
#define BOARD_BATTERY1_A_PER_V (31.f)
@@ -1,3 +0,0 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROMFSROOT=""
-89
View File
@@ -1,89 +0,0 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS7"
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_COMMON_BAROMETERS=y
CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
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
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=y
-13
View File
@@ -1,13 +0,0 @@
{
"board_id": 1013,
"magic": "PX4FWv1",
"description": "Firmware for the MatekH743-slim board",
"image": "",
"build_time": 0,
"summary": "MatekH743-mini",
"version": "0.1",
"image_size": 0,
"image_maxsize": 1835008,
"git_identity": "",
"board_revision": 0
}
@@ -1,24 +0,0 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_A_PER_V 17
param set-default BAT1_N_CELLS 4
param set-default BAT1_V_CHARGED 4.2
param set-default BAT1_V_DIV 10.1
param set-default BAT1_V_EMPTY 3.2
param set-default SYS_HAS_MAG 0
param set-default PWM_MAIN_TIM0 -4
param set-default RC_INPUT_PROTO -1
param set-default IMU_GYRO_RATEMAX 2000
param set-default SYS_AUTOSTART 4001
param set-default MC_PITCHRATE_K 0.4
param set-default MC_ROLLRATE_K 0.35
param set-default MC_YAWRATE_K 1.2
param set-default MC_YAWRATE_MAX 360
param set-default MAV_TYPE 2
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4
param set-default CBRK_SUPPLY_CHK 894281
@@ -1,13 +0,0 @@
#!/bin/sh
#
# board specific extras init
#------------------------------------------------------------------------------
# NxtV1 does not have OSD
# if ! param compare OSD_ATXXXX_CFG 0
# then
# atxxxx start -s
# fi
# DShot telemetry is always on UART7
# dshot telemetry /dev/ttyS5
@@ -1,16 +0,0 @@
#!/bin/sh
#
# board specific sensors init
#------------------------------------------------------------------------------
board_adc start
# # Internal SPI bus BMI088 accel/gyro
bmi088 -s -b 1 -A -R 2 start
bmi088 -s -b 1 -G -R 2 start
bmi088 -s -b 4 -A -R 2 start
bmi088 -s -b 4 -G -R 2 start
# internal baro
spl06 -X -a 0x77 start
@@ -1,17 +0,0 @@
#
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
config BOARD_HAS_PROBES
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
default y
---help---
This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers.
config BOARD_USE_PROBES
bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11"
default n
depends on BOARD_HAS_PROBES
---help---
Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers.
@@ -1,92 +0,0 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DEV_CONSOLE is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_SPI_EXCHANGE is not set
# CONFIG_STM32H7_SYSCFG is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/hkust/nxt-dual/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743VI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=768
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_INITTHREAD_PRIORITY=254
CONFIG_BOARD_LATE_INITIALIZE=y
CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x004b
CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
#TODOally for VENDOR ID in the future
CONFIG_CDCACM_VENDORID=0x3162
CONFIG_CDCACM_VENDORSTR="Matek"
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEFAULT_SMALL=y
CONFIG_EXPERIMENTAL=y
CONFIG_FDCLONE_DISABLE=y
CONFIG_FDCLONE_STDIO=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_INIT_ENTRYPOINT="bootloader_main"
CONFIG_INIT_STACKSIZE=3194
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SPI=y
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=32
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_USART6=y #debug port, can be modified to UART8
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=300
CONFIG_SYSTEMTICK_HOOK=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGINT_CHAR=0x03
CONFIG_TTY_SIGTSTP=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
@@ -1,487 +0,0 @@
/************************************************************************************
* nuttx-configs/px4_fmu-v6u/include/board.h
*
* Copyright (C) 2016-2019 Gregory Nutt. All rights reserved.
* Authors: David Sidrane <david.sidrane@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include "board_dma_map.h"
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
#include "stm32_rcc.h"
#include "stm32_sdmmc.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* The MatekH743-Slim board provides the following clock sources:
*
* X1: 16 MHz crystal for HSE
*
* So we have these clock source available within the STM32
*
* HSI: 16 MHz RC factory-trimmed
* HSE: 16 MHz crystal for HSE
*/
#define STM32_BOARD_XTAL 16000000ul
#define STM32_HSI_FREQUENCY 16000000ul
#define STM32_LSI_FREQUENCY 32000
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
#define STM32_LSE_FREQUENCY 32768
/* Main PLL Configuration.
*
* PLL source is HSE = 16,000,000
*
* PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN
* Subject to:
*
* 1 <= PLLM <= 63
* 4 <= PLLN <= 512
* 150 MHz <= PLL_VCOL <= 420MHz
* 192 MHz <= PLL_VCOH <= 836MHz
*
* SYSCLK = PLL_VCO / PLLP
* CPUCLK = SYSCLK / D1CPRE
* Subject to
*
* PLLP1 = {2, 4, 6, 8, ..., 128}
* PLLP2,3 = {2, 3, 4, ..., 128}
* CPUCLK <= 480 MHz
*/
#define STM32_BOARD_USEHSE
#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE
/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR
*
* PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz
*
* PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz
* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz
*/
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \
RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP1EN | \
RCC_PLLCFGR_DIVQ1EN | \
RCC_PLLCFGR_DIVR1EN)
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1)
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60)
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4)
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8)
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60)
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4)
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8)
/* PLL2 */
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \
RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP2EN | \
RCC_PLLCFGR_DIVQ2EN | \
RCC_PLLCFGR_DIVR2EN)
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4)
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48)
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2)
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2)
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2)
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48)
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
/* PLL3 */
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \
RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVQ3EN)
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4)
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48)
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2)
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4)
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2)
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48)
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4)
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
/* SYSCLK = PLL1P = 480MHz
* CPUCLK = SYSCLK / 1 = 480 MHz
*/
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1)
/* Configure Clock Assignments */
/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max)
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240
*/
#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */
#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */
#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */
#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */
#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */
#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* Timer clock frequencies */
/* Timers driven from APB1 will be twice PCLK1 */
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
/* Timers driven from APB2 will be twice PCLK2 */
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY)
/* Kernel Clock Configuration
*
* Note: look at Table 54 in ST Manual
*/
/* I2C123 clock source */
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI
/* I2C4 clock source */
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI
/* SPI123 clock source */
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2
/* SPI45 clock source */
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2
/* SPI6 clock source */
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2
/* USB 1 and 2 clock source */
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3
/* ADC 1 2 3 clock source */
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2
/* FDCAN 1 clock source */
// #define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */
#define STM32_FDCANCLK STM32_HSE_FREQUENCY
/* FLASH wait states
*
* ------------ ---------- -----------
* Vcore MAX ACLK WAIT STATES
* ------------ ---------- -----------
* 1.15-1.26 V 70 MHz 0
* (VOS1 level) 140 MHz 1
* 210 MHz 2
* 1.05-1.15 V 55 MHz 0
* (VOS2 level) 110 MHz 1
* 165 MHz 2
* 220 MHz 3
* 0.95-1.05 V 45 MHz 0
* (VOS3 level) 90 MHz 1
* 135 MHz 2
* 180 MHz 3
* 225 MHz 4
* ------------ ---------- -----------
*/
#define BOARD_FLASH_WAITSTATES 2
/* SDMMC definitions ********************************************************/
/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
*/
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
/* LED definitions ******************************************************************/
/* The board has two, LED_GREEN a Green LED and LED_BLUE a Blue LED,
* that can be controlled by software.
*
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.
* The following definitions are used to access individual LEDs.
*/
/* LED index values for use with board_userled() */
#define BOARD_LED1 0
#define BOARD_LED2 1
#define BOARD_LED3 2
#define BOARD_NLEDS 3
#define BOARD_LED_RED BOARD_LED1
#define BOARD_LED_GREEN BOARD_LED2
#define BOARD_LED_BLUE BOARD_LED3
/* LED bits for use with board_userled_all() */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
#define BOARD_LED2_BIT (1 << BOARD_LED2)
#define BOARD_LED3_BIT (1 << BOARD_LED3)
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
* events as follows:
*
*
* SYMBOL Meaning LED state
* Red Green Blue
* ---------------------- -------------------------- ------ ------ ----*/
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */
/* Thus if the Green LED is statically on, NuttX has successfully booted and
* is, apparently, running normally. If the Red LED is flashing at
* approximately 2Hz, then a fatal error has been detected and the system
* has halted.
*/
/* Alternate function pin selections ************************************************/
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PBA10 */
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */
#define GPIO_USART1_CK GPIO_USART1_CK /* PB8 NC */
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART2_CK GPIO_USART2_CK_2 /* PD7 NC */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_USART3_CK GPIO_USART3_CK_3 /* PD10 NC */
#define GPIO_UART4_RX GPIO_UART4_RX_3 /* PB8 */
#define GPIO_UART4_TX GPIO_UART4_TX_3 /* PB9 */
#define GPIO_UART5_RX GPIO_UART5_RX_1 /* PB12 */
#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 NC */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
/* SPI
*
*/
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PC3 */
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_5) /* PD3 */
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */
#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PB3 */
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE5 */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */
#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_2) /* PE2 */
/* I2C
*
*
*/
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 /* PB6 */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_1 /* PD12 */
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_1 /* PD13 */
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN12)
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTD | GPIO_PIN13)
/* SDMMC1
*
* SDMMC1_D0 PC8
* SDMMC1_D1 PC9
* SDMMC1_D2 PC10
* SDMMC1_D3 PC11
* SDMMC1_CK PC12
* SDMMC1_CMD PD2
*/
// #define GPIO_SDMMC1_D0 GPIO_SDMMC1_D0 /* PC8 */
// #define GPIO_SDMMC1_D1 GPIO_SDMMC1_D1 /* PC9 */
// #define GPIO_SDMMC1_D2 GPIO_SDMMC1_D2 /* PC10 */
// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3 /* PC11 */
// #define GPIO_SDMMC1_CK GPIO_SDMMC1_CK /* PC12 */
// #define GPIO_SDMMC1_CMD GPIO_SDMMC1_CMD /* PD2 */
/* USB
*
* OTG_FS_DM PA11
* OTG_FS_DP PA12
* VBUS PA9
*/
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
// #if defined(CONFIG_BOARD_USE_PROBES)
// # include "stm32_gpio.h"
// # define PROBE_N(n) (1<<((n)-1))
// # define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */
// # define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */
// # define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */
// # define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */
// # define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */
// # define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */
// # define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */
// # define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */
// # define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */
// # define PROBE_INIT(mask) \
// do { \
// if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
// if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
// if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
// if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
// if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
// if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
// if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \
// if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \
// if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \
// } while(0)
// # define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
// # define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
// #else
// # define PROBE_INIT(mask)
// # define PROBE(n,s)
// # define PROBE_MARK(n)
// #endif
#endif /*__NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H */
@@ -1,62 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
// #define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
// #define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
// DMAMUX2
// #define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_0 /* DMA1:61 */
// #define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_0 /* DMA1:62 */
// #define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
// #define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
//TODO: UART DMA test
// #define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_1 /*DMA2:41*/
// #define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_1 /*DMA2:42*/
// #define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2:43 */
// #define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* DMA2:44 */
// #define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* DMA2:45 */
// #define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* DMA2:46 */
#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_1 /* DMA1:63 */
#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_1 /* DMA1:64 */
// #define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_0 /* DMA1:65 */
// #define DMAMAP_UART5_TX DMAMAP_DMA12_UART5RX_0 /* DMA1:66 */
@@ -1,288 +0,0 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_ENVIRON is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_DISABLE_PTHREAD is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_CAT is not set
# CONFIG_NSH_DISABLE_CD is not set
# CONFIG_NSH_DISABLE_CP is not set
# CONFIG_NSH_DISABLE_DATE is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_ECHO is not set
# CONFIG_NSH_DISABLE_ENV is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_EXPORT is not set
# CONFIG_NSH_DISABLE_FREE is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_HELP is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_KILL is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_LS is not set
# CONFIG_NSH_DISABLE_MKDIR is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_MOUNT is not set
# CONFIG_NSH_DISABLE_MV is not set
# CONFIG_NSH_DISABLE_PRINTF is not set
# CONFIG_NSH_DISABLE_PS is not set
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
# CONFIG_NSH_DISABLE_PWD is not set
# CONFIG_NSH_DISABLE_RM is not set
# CONFIG_NSH_DISABLE_RMDIR is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_SET is not set
# CONFIG_NSH_DISABLE_SLEEP is not set
# CONFIG_NSH_DISABLE_SOURCE is not set
# CONFIG_NSH_DISABLE_TEST is not set
# CONFIG_NSH_DISABLE_TIME is not set
# CONFIG_NSH_DISABLE_UMOUNT is not set
# CONFIG_NSH_DISABLE_UNSET is not set
# CONFIG_NSH_DISABLE_USLEEP is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/hkust/nxt-dual/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743VI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=768
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU_EARLY_RESET=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0036
CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x1B8C
CONFIG_CDCACM_VENDORSTR="Matek"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_MEMFAULT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=n
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_IOB_NBUFFERS=24
CONFIG_IOB_NCHAINS=24
CONFIG_INIT_ENTRYPOINT="nsh_main"
CONFIG_INIT_STACKSIZE=3194
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_MAX_EXITFUNS=1
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_IOB=y
CONFIG_MM_REGIONS=4
# Avaible in Dual Version TODO: MTD IO error
CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_PROGMEM=y
CONFIG_MTD_RAMTRON=y
CONFIG_MTD_W25=y
CONFIG_MTD_W25QXXXJV=y
CONFIG_NAME_MAX=40
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_OTG_ID_GPIO_DISABLE=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_SETSPEED=y
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_READLINE_TABCOMPLETION=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SIG_SIGWORK=4
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_STM32H7_ADC1=y
CONFIG_STM32H7_ADC2=y
CONFIG_STM32H7_ADC3=y #should always enable otherwsie got ADC timeout error this is for tempreature compenstae
CONFIG_STM32H7_BBSRAM=y
CONFIG_STM32H7_BBSRAM_FILES=5
CONFIG_STM32H7_BDMA=y
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_FLASH_OVERRIDE_I=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C4=y
CONFIG_STM32H7_I2C_DYNTIMEO=y
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_RTC=y
CONFIG_STM32H7_RTC_HSECLOCK=y
CONFIG_STM32H7_RTC_MAGIC_REG=1
CONFIG_STM32H7_SAVE_CRASHDUMP=y
CONFIG_STM32H7_SDMMC1=y
CONFIG_STM32H7_SDMMC1_DMA=y
CONFIG_STM32H7_SDMMC1_DMA_BUFFER=1024
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
# CONFIG_STM32H7_SPI1_DMA=y
# CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI2_DMA=y
CONFIG_STM32H7_SPI2_DMA_BUFFER=4096
CONFIG_STM32H7_SPI3=y
# CONFIG_STM32H7_SPI3_DMA=y
# CONFIG_STM32H7_SPI3_DMA_BUFFER=1024
CONFIG_STM32H7_SPI4=y
# CONFIG_STM32H7_SPI4_DMA=y
# CONFIG_STM32H7_SPI4_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
CONFIG_STM32H7_SPI_DMATHRESHOLD=8
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM2=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y
# CONFIG_STM32H7_TIM5=y
# CONFIG_STM32H7_TIM6=y
# CONFIG_STM32H7_TIM7=y
CONFIG_STM32H7_TIM8=y
CONFIG_STM32H7_USART1=y #ttyS0
CONFIG_STM32H7_USART2=y #ttyS1
CONFIG_STM32H7_USART3=y #ttyS2
CONFIG_STM32H7_UART4=y #ttyS3
CONFIG_STM32H7_UART5=y #ttyS4
CONFIG_STM32H7_USART6=y #ttyS5 NC
CONFIG_STM32H7_UART7=y #ttyS6
CONFIG_STM32H7_UART8=y #ttyS7
CONFIG_STM32H7_USART_BREAKS=y
CONFIG_STM32H7_USART_INVERT=y
CONFIG_STM32H7_USART_SINGLEWIRE=y
CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=3000
CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=180
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_UART4_BAUD=921600
CONFIG_UART4_RXBUFSIZE=3000
CONFIG_UART4_TXBUFSIZE=3000
CONFIG_UART4_RXDMA=y
CONFIG_UART4_TXDMA=y
CONFIG_UART5_BAUD=57600
CONFIG_UART5_RXBUFSIZE=600
CONFIG_UART5_TXBUFSIZE=1500
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=180
CONFIG_USART6_SERIAL_CONSOLE=y
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_TXBUFSIZE=3000
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=3000
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_WATCHDOG=y
CONFIG_WQUEUE_NOTIFIER=y
@@ -1,271 +0,0 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_ENVIRON is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_TIME is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/hkust/nxt/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743VI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU_EARLY_RESET=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=95751
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0036
CONFIG_CDCACM_PRODUCTSTR="NxtPX4"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x1B8C
CONFIG_CDCACM_VENDORSTR="Gumstix"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_MEMFAULT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_IOB_NBUFFERS=24
CONFIG_IOB_NCHAINS=24
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_IOB=y
CONFIG_MM_REGIONS=4
# CONFIG_MTD=y
# CONFIG_MTD_BYTE_WRITE=y
# CONFIG_MTD_PARTITION=y
# CONFIG_MTD_PROGMEM=y
# CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_OTG_ID_GPIO_DISABLE=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_SETSPEED=y
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_READLINE_TABCOMPLETION=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
# CONFIG_SDMMC2_SDIO_PULLUP=y
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SIG_SIGWORK=4
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_STM32H7_ADC1=y
CONFIG_STM32H7_ADC3=y
CONFIG_STM32H7_BBSRAM=y
CONFIG_STM32H7_BBSRAM_FILES=5
CONFIG_STM32H7_BDMA=y
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_FLASH_OVERRIDE_I=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C2=y
# CONFIG_STM32H7_I2C3=y
# CONFIG_STM32H7_I2C4=y
CONFIG_STM32H7_I2C_DYNTIMEO=y
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_RTC=y
CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y
CONFIG_STM32H7_RTC_MAGIC_REG=1
CONFIG_STM32H7_SAVE_CRASHDUMP=y
CONFIG_STM32H7_SDMMC1=y
CONFIG_STM32H7_SDMMC1_DMA=y
CONFIG_STM32H7_SDMMC1_DMA_BUFFER=1024
# CONFIG_STM32H7_SDMMC2=y
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI2_DMA=y
CONFIG_STM32H7_SPI2_DMA_BUFFER=4096
CONFIG_STM32H7_SPI3=y
CONFIG_STM32H7_SPI3_DMA=y
CONFIG_STM32H7_SPI3_DMA_BUFFER=1024
# CONFIG_STM32H7_SPI5=y
# CONFIG_STM32H7_SPI6=y
# CONFIG_STM32H7_SPI6_DMA=y
# CONFIG_STM32H7_SPI6_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
# CONFIG_STM32H7_TIM12=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_TIM5=y
CONFIG_STM32H7_USART1=y #ttyS0
CONFIG_STM32H7_USART2=y #ttyS1
CONFIG_STM32H7_USART3=y #ttyS2
CONFIG_STM32H7_UART4=y #ttyS3
CONFIG_STM32H7_UART5=y #ttyS4
CONFIG_STM32H7_UART7=y #ttyS5
# CONFIG_STM32H7_USART_BREAKS=y
# CONFIG_STM32H7_USART_INVERT=y
# CONFIG_STM32H7_USART_SINGLEWIRE=y
# CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
# CONFIG_UART5_IFLOWCONTROL=y
# CONFIG_UART5_OFLOWCONTROL=y
# CONFIG_UART8_BAUD=57600
# CONFIG_UART8_RXBUFSIZE=600
# CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
# CONFIG_USART2_IFLOWCONTROL=y
# CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=3000
CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=180
CONFIG_USART3_SERIAL_CONSOLE=y
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_UART4_BAUD=921600
CONFIG_UART4_RXBUFSIZE=3000
CONFIG_UART4_TXBUFSIZE=1200
# CONFIG_UART4_RXDMA=y
# CONFIG_UART4_TXDMA=y
CONFIG_UART5_BAUD=57600
CONFIG_UART5_RXBUFSIZE=600
CONFIG_UART5_TXBUFSIZE=1500
# CONFIG_USART6_BAUD=57600
# CONFIG_USART6_RXBUFSIZE=600
# CONFIG_USART6_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
# CONFIG_UART7_IFLOWCONTROL=y
# CONFIG_UART7_OFLOWCONTROL=y
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_TXBUFSIZE=3000
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y
CONFIG_WQUEUE_NOTIFIER=y
@@ -1,213 +0,0 @@
/****************************************************************************
* scripts/script.ld
*
* Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory.
* The flash memory is partitioned into a User Flash memory and a System
* Flash memory. Each of these memories has two banks:
*
* 1) User Flash memory:
*
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each
*
* 2) System Flash memory:
*
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector
*
* 3) User option bytes for user configuration, only in Bank 1.
*
* In the STM32H743II, two different boot spaces can be selected through
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
* BOOT_ADD1 option bytes:
*
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
* ST programmed value: Flash memory at 0x0800:0000
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
* ST programmed value: System bootloader at 0x1FF0:0000
*
* The Durandal has a Swtich on board, the BOOT0 pin is at ground so by default,
* the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is
* drepresed, then the boot will be from 0x1FF0:0000
*
* The STM32H743ZI also has 1024Kb of data SRAM.
* SRAM is split up into several blocks and into three power domains:
*
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus
*
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000
*
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit
* DTCM ports. The DTCM-RAM could be used for critical real-time
* data, such as interrupt service routines or stack / heap memory.
* Both DTCM-RAMs can be used in parallel (for load/store operations)
* thanks to the Cortex-M7 dual issue capability.
*
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000
*
* This RAM is connected to ITCM 64-bit interface designed for
* execution of critical real-times routines by the CPU.
*
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA
* through D1 domain AXI bus matrix
*
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000
*
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA
* through D2 domain AHB bus matrix
*
* 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000
*
* SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000
*
* 4) AHB SRAM (D3 domain) accessible by most of system masters
* through D3 domain AHB bus matrix
*
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address range.
*/
MEMORY
{
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K
dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K
sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K
sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K
sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K
sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K
bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
EXTERN(_bootdelay_signature)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(32);
/*
This signature provides the bootloader with a way to delay booting
*/
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}
@@ -1,228 +0,0 @@
/****************************************************************************
* scripts/script.ld
*
* Copyright (C) 2020 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The board uses an STM32H743II and has 2048Kb of main FLASH memory.
* The flash memory is partitioned into a User Flash memory and a System
* Flash memory. Each of these memories has two banks:
*
* 1) User Flash memory:
*
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each
*
* 2) System Flash memory:
*
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector
*
* 3) User option bytes for user configuration, only in Bank 1.
*
* In the STM32H743II, two different boot spaces can be selected through
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
* BOOT_ADD1 option bytes:
*
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
* ST programmed value: Flash memory at 0x0800:0000
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
* ST programmed value: System bootloader at 0x1FF0:0000
*
* There's a switch on board, the BOOT0 pin is at ground so by default,
* the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is
* drepresed, then the boot will be from 0x1FF0:0000
*
* The STM32H743ZI also has 1024Kb of data SRAM.
* SRAM is split up into several blocks and into three power domains:
*
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus
*
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000
*
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit
* DTCM ports. The DTCM-RAM could be used for critical real-time
* data, such as interrupt service routines or stack / heap memory.
* Both DTCM-RAMs can be used in parallel (for load/store operations)
* thanks to the Cortex-M7 dual issue capability.
*
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000
*
* This RAM is connected to ITCM 64-bit interface designed for
* execution of critical real-times routines by the CPU.
*
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA
* through D1 domain AXI bus matrix
*
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000
*
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA
* through D2 domain AHB bus matrix
*
* 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000
*
* SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000
*
* 4) AHB SRAM (D3 domain) accessible by most of system masters
* through D3 domain AHB bus matrix
*
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address range.
*/
MEMORY
{
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */
SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */
SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */
SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */
BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
EXTERN(_bootdelay_signature)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(32);
/*
This signature provides the bootloader with a way to delay booting
*/
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > FLASH
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > FLASH
.ARM.extab : {
*(.ARM.extab*)
} > FLASH
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > FLASH
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
/* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */
. = ALIGN(16);
FILL(0xffff)
. += 16;
} > AXI_SRAM AT > FLASH = 0xffff
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > AXI_SRAM
/* Emit the the D3 power domain section for locating BDMA data */
.sram4_reserve (NOLOAD) :
{
*(.sram4)
. = ALIGN(4);
_sram4_heap_start = ABSOLUTE(.);
} > SRAM4
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}
-69
View File
@@ -1,69 +0,0 @@
############################################################################
#
# Copyright (c) 2021 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
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
add_library(drivers_board
bootloader_main.c
usb.c
)
target_link_libraries(drivers_board
PRIVATE
nuttx_arch
nuttx_drivers
bootloader
)
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common)
else()
add_library(drivers_board
i2c.cpp
init.c
led.c
sdio.c
spi.cpp
timer_config.cpp
usb.c
mtd.cpp
)
# add_dependencies(drivers_board arch_board_hw_info)
target_link_libraries(drivers_board
PRIVATE
arch_io_pins
arch_spi
arch_board_hw_info
drivers__led
nuttx_arch
nuttx_drivers
px4_layer
)
endif()
-230
View File
@@ -1,230 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file board_config.h
*
* Board internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32_gpio.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
#define FLASH_BASED_PARAMS
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */
# define GPIO_nLED_RED /* PD15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN15)
# define GPIO_nLED_GREEN /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11)
# define GPIO_nLED_BLUE /* PB15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
# define BOARD_HAS_CONTROL_STATUS_LEDS 1
# define BOARD_OVERLOAD_LED LED_RED
# define BOARD_ARMED_STATE_LED LED_BLUE
/* I2C busses */
/* Devices on the onboard buses.
*
* Note that these are unshifted addresses.
*/
// #define PX4_I2C_OBDEV_SE050 0x48
#define GPIO_SPL_ADDR_SET /* PB5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN5)
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that
* can be used by the Px4 Firmware in the adc driver
*/
/* ADC defines to be used in sensors.cpp to read from a particular channel */
#define SYSTEM_ADC_BASE STM32_ADC1_BASE
#define ADC12_CH(n) (n)
#define PX4_ADC_GPIO \
/* PC4 */ GPIO_ADC12_INP4, \
/* PC5 */ GPIO_ADC12_INP8
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_BATTERY_VOLTAGE_CHANNEL ADC12_CH(4)
#define ADC_BATTERY_CURRENT_CHANNEL ADC12_CH(5)
#define ADC_CHANNELS \
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY_CURRENT_CHANNEL))
#define BOARD_ADC_OPEN_CIRCUIT_V (1.6f)
/* Define Battery 1 Voltage Divider and A per V
*/
// #define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */
// #define BOARD_BATTERY1_A_PER_V (40.0f)
// #define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */
/* PWM
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 8
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/* Spare GPIO */
#define GPIO_PA4 /* PA4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN4)
#define GPIO_PC0 /* PC0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0)
#define GPIO_PC1 /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
/* Tone alarm output */
#define TONE_ALARM_TIMER 4 /* Timer 4 */
#define TONE_ALARM_CHANNEL 3 /* PD14 GPIO_TIM4_CH3 NC */
/*NC can be modified with Spare GPIO then connected with hardware */
#define GPIO_BUZZER_1 /* PA4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN4)
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
#define GPIO_TONE_ALARM GPIO_BUZZER_1
/* USB OTG FS
*
* PD0 OTG_FS_VBUS VBUS sensing
*/
#define GPIO_OTGFS_VBUS /* PD0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTD|GPIO_PIN0)
#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS))
/* High-resolution timer */
#define HRT_TIMER 8 /* use timer1 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS4"
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
// #define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
// #define RC_INVERT_INPUT(_invert_true) px4_arch_gpiowrite(GPIO_SBUS_INV, _invert_true);
/* SD card bringup does not work if performed on the IDLE thread because it
* will cause waiting. Use either:
*
* CONFIG_LIB_BOARDCTL=y, OR
* CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y
*/
#define SDIO_SLOTNO 0 /* Only one slot */
#define SDIO_MINOR 0
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \
!defined(CONFIG_BOARD_INITTHREAD)
# warning SDIO initialization cannot be perfomed on the IDLE thread
#endif
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_TONE_ALARM_IDLE, \
GPIO_SPL_ADDR_SET, \
GPIO_PC0, \
GPIO_PC1, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_NUM_IO_TIMERS 5
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void);
/****************************************************************************************************
* Name: stm32_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the board.
*
****************************************************************************************************/
extern void stm32_spiinitialize(void);
extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS
@@ -1,75 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file bootloader_main.c
*
* FMU-specific early startup code for bootloader
*/
#include "board_config.h"
#include "bl.h"
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <chip.h>
#include <stm32_uart.h>
#include <arch/board/board.h>
#include "arm_internal.h"
#include <px4_platform_common/init.h>
extern int sercon_main(int c, char **argv);
__EXPORT void board_on_reset(int status) {}
__EXPORT void stm32_boardinitialize(void)
{
/* configure USB interfaces */
stm32_usbinitialize();
}
__EXPORT int board_app_initialize(uintptr_t arg)
{
return 0;
}
void board_late_initialize(void)
{
sercon_main(0, NULL);
}
extern void sys_tick_handler(void);
void board_timerhook(void)
{
sys_tick_handler();
}
-505
View File
@@ -1,505 +0,0 @@
/****************************************************************************
*
* 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file flash_w25q128.c
*
* Board-specific external flash W25Q128 functions.
*/
#include "board_config.h"
#include "qspi.h"
#include "arm_internal.h"
#include <assert.h>
#include <debug.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Configuration ********************************************************************/
#define N25Q128_SECTOR_SIZE (4*1024)
#define N25Q128_SECTOR_SHIFT (12)
#define N25Q128_SECTOR_COUNT (4096)
#define N25Q128_PAGE_SIZE (256)
#define N25Q128_PAGE_SHIFT (8)
#define W25Q_DUMMY_CYCLES_FAST_READ_QUAD 6
#define W25Q_INSTR_FAST_READ_QUAD 0xEB
#define W25Q_ADDRESS_SIZE 3 // 3 bytes -> 24 bits
#define N25QXXX_READ_STATUS 0x05 /* Read status register: *
* 0x05 | SR */
#define N25QXXX_PAGE_PROGRAM 0x02 /* Page Program: *
* 0x02 | ADDR(MS) | ADDR(MID) | *
* ADDR(LS) | data */
#define N25QXXX_WRITE_ENABLE 0x06 /* Write enable: *
* 0x06 */
#define N25QXXX_WRITE_DISABLE 0x04 /* Write disable command code: *
* 0x04 */
#define N25QXXX_SUBSECTOR_ERASE 0x20 /* Sub-sector Erase (4 kB) *
* 0x20 | ADDR(MS) | ADDR(MID) | *
* ADDR(LS) */
/* N25QXXX Registers ****************************************************************/
/* Status register bit definitions */
#define STATUS_BUSY_MASK (1 << 0) /* Bit 0: Device ready/busy status */
# define STATUS_READY (0 << 0) /* 0 = Not Busy */
# define STATUS_BUSY (1 << 0) /* 1 = Busy */
#define STATUS_WEL_MASK (1 << 1) /* Bit 1: Write enable latch status */
# define STATUS_WEL_DISABLED (0 << 1) /* 0 = Not Write Enabled */
# define STATUS_WEL_ENABLED (1 << 1) /* 1 = Write Enabled */
#define STATUS_BP_SHIFT (2) /* Bits 2-4: Block protect bits */
#define STATUS_BP_MASK (7 << STATUS_BP_SHIFT)
# define STATUS_BP_NONE (0 << STATUS_BP_SHIFT)
# define STATUS_BP_ALL (7 << STATUS_BP_SHIFT)
#define STATUS_TB_MASK (1 << 5) /* Bit 5: Top / Bottom Protect */
# define STATUS_TB_TOP (0 << 5) /* 0 = BP2-BP0 protect Top down */
# define STATUS_TB_BOTTOM (1 << 5) /* 1 = BP2-BP0 protect Bottom up */
#define STATUS_BP3_MASK (1 << 5) /* Bit 6: BP3 */
#define STATUS_SRP0_MASK (1 << 7) /* Bit 7: Status register protect 0 */
# define STATUS_SRP0_UNLOCKED (0 << 7) /* 0 = WP# no effect / PS Lock Down */
# define STATUS_SRP0_LOCKED (1 << 7) /* 1 = WP# protect / OTP Lock Down */
/************************************************************************************
* Private Types
************************************************************************************/
/* This type represents the state of the MTD device. The struct mtd_dev_s must
* appear at the beginning of the definition so that you can freely cast between
* pointers to struct mtd_dev_s and struct n25qxxx_dev_s.
*/
struct n25qxxx_dev_s {
//struct mtd_dev_s mtd; /* MTD interface */
FAR struct qspi_dev_s *qspi; /* Saved QuadSPI interface instance */
uint16_t nsectors; /* Number of erase sectors */
uint8_t sectorshift; /* Log2 of sector size */
uint8_t pageshift; /* Log2 of page size */
FAR uint8_t *cmdbuf; /* Allocated command buffer */
FAR uint8_t *readbuf; /* Allocated status read buffer */
};
/****************************************************************************
* Private Data
****************************************************************************/
struct qspi_dev_s *ptr_qspi_dev;
struct qspi_meminfo_s qspi_meminfo = {
.flags = QSPIMEM_QUADIO,
.addrlen = W25Q_ADDRESS_SIZE,
.dummies = W25Q_DUMMY_CYCLES_FAST_READ_QUAD,
.cmd = W25Q_INSTR_FAST_READ_QUAD
};
struct n25qxxx_dev_s n25qxxx_dev;
uint8_t cmdbuf[4] = {0u};
uint8_t readbuf[1] = {0u};
/************************************************************************************
* Private Functions
************************************************************************************/
__ramfunc__ int n25qxxx_command(FAR struct qspi_dev_s *qspi, uint8_t cmd);
__ramfunc__ uint8_t n25qxxx_read_status(FAR struct n25qxxx_dev_s *priv);
__ramfunc__ int n25qxxx_command_read(FAR struct qspi_dev_s *qspi, uint8_t cmd,
FAR void *buffer, size_t buflen);
__ramfunc__ void n25qxxx_write_enable(FAR struct n25qxxx_dev_s *priv);
__ramfunc__ void n25qxxx_write_disable(FAR struct n25qxxx_dev_s *priv);
__ramfunc__ int n25qxxx_write_page(struct n25qxxx_dev_s *priv, FAR const uint8_t *buffer,
off_t address, size_t buflen);
__ramfunc__ int n25qxxx_write_one_page(struct n25qxxx_dev_s *priv, struct qspi_meminfo_s *meminfo);
__ramfunc__ int n25qxxx_erase_sector(struct n25qxxx_dev_s *priv, off_t sector);
__ramfunc__ bool n25qxxx_isprotected(FAR struct n25qxxx_dev_s *priv, uint8_t status,
off_t address);
__ramfunc__ int n25qxxx_command_address(FAR struct qspi_dev_s *qspi, uint8_t cmd,
off_t addr, uint8_t addrlen);
/************************************************************************************
* Public Functions
************************************************************************************/
void flash_w25q128_init(void)
{
int qspi_interface_number = 0;
ptr_qspi_dev = stm32h7_qspi_initialize(qspi_interface_number);
n25qxxx_dev.qspi = ptr_qspi_dev;
n25qxxx_dev.cmdbuf = cmdbuf;
n25qxxx_dev.readbuf = readbuf;
n25qxxx_dev.sectorshift = N25Q128_SECTOR_SHIFT;
n25qxxx_dev.pageshift = N25Q128_PAGE_SHIFT;
n25qxxx_dev.nsectors = N25Q128_SECTOR_COUNT;
}
__ramfunc__ ssize_t up_progmem_ext_getpage(size_t addr)
{
ssize_t page_address = (addr - STM32_FMC_BANK4) / N25Q128_SECTOR_COUNT;
return page_address;
}
__ramfunc__ ssize_t up_progmem_ext_eraseblock(size_t block)
{
ssize_t size = N25Q128_SECTOR_COUNT;
irqstate_t irqstate = px4_enter_critical_section();
stm32h7_qspi_exit_memorymapped(ptr_qspi_dev);
n25qxxx_erase_sector(&n25qxxx_dev, block);
stm32h7_qspi_enter_memorymapped(ptr_qspi_dev, &qspi_meminfo, 0);
px4_leave_critical_section(irqstate);
return size;
}
__ramfunc__ ssize_t up_progmem_ext_write(size_t addr, FAR const void *buf, size_t count)
{
ssize_t ret_val = 0;
irqstate_t irqstate = px4_enter_critical_section();
stm32h7_qspi_exit_memorymapped(ptr_qspi_dev);
addr &= 0xFFFFFF;
n25qxxx_write_page(&n25qxxx_dev, buf, (off_t)addr, count);
stm32h7_qspi_enter_memorymapped(ptr_qspi_dev, &qspi_meminfo, 0);
px4_leave_critical_section(irqstate);
return ret_val;
}
/************************************************************************************
* Name: n25qxxx_command
************************************************************************************/
__ramfunc__ int n25qxxx_command(FAR struct qspi_dev_s *qspi, uint8_t cmd)
{
struct qspi_cmdinfo_s cmdinfo;
finfo("CMD: %02" PRIx8 "\n", cmd);
cmdinfo.flags = 0;
cmdinfo.addrlen = 0;
cmdinfo.cmd = cmd;
cmdinfo.buflen = 0;
cmdinfo.addr = 0;
cmdinfo.buffer = NULL;
int rv;
rv = qspi_command(qspi, &cmdinfo);
return rv;
}
/************************************************************************************
* Name: n25qxxx_read_status
************************************************************************************/
__ramfunc__ uint8_t n25qxxx_read_status(FAR struct n25qxxx_dev_s *priv)
{
DEBUGVERIFY(n25qxxx_command_read(priv->qspi, N25QXXX_READ_STATUS,
(FAR void *)&priv->readbuf[0], 1));
return priv->readbuf[0];
}
/************************************************************************************
* Name: n25qxxx_command_read
************************************************************************************/
__ramfunc__ int n25qxxx_command_read(FAR struct qspi_dev_s *qspi, uint8_t cmd,
FAR void *buffer, size_t buflen)
{
struct qspi_cmdinfo_s cmdinfo;
finfo("CMD: %02" PRIx8 " buflen: %zu\n", cmd, buflen);
cmdinfo.flags = QSPICMD_READDATA;
cmdinfo.addrlen = 0;
cmdinfo.cmd = cmd;
cmdinfo.buflen = buflen;
cmdinfo.addr = 0;
cmdinfo.buffer = buffer;
int rv;
rv = qspi_command(qspi, &cmdinfo);
return rv;
}
/************************************************************************************
* Name: n25qxxx_write_enable
************************************************************************************/
__ramfunc__ void n25qxxx_write_enable(FAR struct n25qxxx_dev_s *priv)
{
uint8_t status;
do {
n25qxxx_command(priv->qspi, N25QXXX_WRITE_ENABLE);
status = n25qxxx_read_status(priv);
} while ((status & STATUS_WEL_MASK) != STATUS_WEL_ENABLED);
}
/************************************************************************************
* Name: n25qxxx_write_disable
************************************************************************************/
__ramfunc__ void n25qxxx_write_disable(FAR struct n25qxxx_dev_s *priv)
{
uint8_t status;
do {
n25qxxx_command(priv->qspi, N25QXXX_WRITE_DISABLE);
status = n25qxxx_read_status(priv);
} while ((status & STATUS_WEL_MASK) != STATUS_WEL_DISABLED);
}
/************************************************************************************
* Name: n25qxxx_write_page
************************************************************************************/
__ramfunc__ int n25qxxx_write_page(struct n25qxxx_dev_s *priv, FAR const uint8_t *buffer,
off_t address, size_t buflen)
{
struct qspi_meminfo_s meminfo;
unsigned int pagesize;
unsigned int npages;
unsigned int firstpagesize = 0;
int ret = OK;
unsigned int i;
finfo("address: %08jx buflen: %zu\n", (intmax_t)address, buflen);
pagesize = (1 << priv->pageshift);
/* Set up non-varying parts of transfer description */
meminfo.flags = QSPIMEM_WRITE;
meminfo.cmd = N25QXXX_PAGE_PROGRAM;
meminfo.addrlen = 3;
meminfo.dummies = 0;
meminfo.buffer = (void *)buffer;
if (0 != (address % pagesize)) {
firstpagesize = pagesize - (address % pagesize);
}
if (buflen <= firstpagesize) {
meminfo.addr = address;
meminfo.buflen = buflen;
ret = n25qxxx_write_one_page(priv, &meminfo);
} else {
if (firstpagesize > 0) {
meminfo.addr = address;
meminfo.buflen = firstpagesize;
ret = n25qxxx_write_one_page(priv, &meminfo);
buffer += firstpagesize;
address += firstpagesize;
buflen -= firstpagesize;
}
npages = (buflen >> priv->pageshift);
meminfo.buflen = pagesize;
/* Then write each page */
for (i = 0; (i < npages) && (ret == OK); i++) {
/* Set up varying parts of the transfer description */
meminfo.addr = address;
meminfo.buffer = (void *)buffer;
ret = n25qxxx_write_one_page(priv, &meminfo);
/* Update for the next time through the loop */
buffer += pagesize;
address += pagesize;
buflen -= pagesize;
}
if ((ret == OK) && (buflen > 0)) {
meminfo.addr = address;
meminfo.buffer = (void *)buffer;
meminfo.buflen = buflen;
ret = n25qxxx_write_one_page(priv, &meminfo);
}
}
return ret;
}
__ramfunc__ int n25qxxx_write_one_page(struct n25qxxx_dev_s *priv, struct qspi_meminfo_s *meminfo)
{
int ret;
n25qxxx_write_enable(priv);
ret = qspi_memory(priv->qspi, meminfo);
n25qxxx_write_disable(priv);
if (ret < 0) {
ferr("ERROR: QSPI_MEMORY failed writing address=%06" PRIx32 "\n",
meminfo->addr);
}
return ret;
}
/************************************************************************************
* Name: n25qxxx_erase_sector
************************************************************************************/
__ramfunc__ int n25qxxx_erase_sector(struct n25qxxx_dev_s *priv, off_t sector)
{
off_t address;
uint8_t status;
finfo("sector: %08jx\n", (intmax_t) sector);
/* Check that the flash is ready and unprotected */
status = n25qxxx_read_status(priv);
if ((status & STATUS_BUSY_MASK) != STATUS_READY) {
ferr("ERROR: Flash busy: %02" PRIx8, status);
return -EBUSY;
}
/* Get the address associated with the sector */
address = (off_t)sector << priv->sectorshift;
if ((status & (STATUS_BP3_MASK | STATUS_BP_MASK)) != 0 &&
n25qxxx_isprotected(priv, status, address)) {
ferr("ERROR: Flash protected: %02" PRIx8, status);
return -EACCES;
}
/* Send the sector erase command */
n25qxxx_write_enable(priv);
n25qxxx_command_address(priv->qspi, N25QXXX_SUBSECTOR_ERASE, address, 3);
/* Wait for erasure to finish */
while ((n25qxxx_read_status(priv) & STATUS_BUSY_MASK) != 0);
return OK;
}
/************************************************************************************
* Name: n25qxxx_isprotected
************************************************************************************/
__ramfunc__ bool n25qxxx_isprotected(FAR struct n25qxxx_dev_s *priv, uint8_t status,
off_t address)
{
off_t protstart;
off_t protend;
off_t protsize;
unsigned int bp;
/* The BP field is spread across non-contiguous bits */
bp = (status & STATUS_BP_MASK) >> STATUS_BP_SHIFT;
if (status & STATUS_BP3_MASK) {
bp |= 8;
}
/* the BP field is essentially the power-of-two of the number of 64k sectors,
* saturated to the device size.
*/
if (0 == bp) {
return false;
}
protsize = 0x00010000;
protsize <<= (protsize << (bp - 1));
protend = (1 << priv->sectorshift) * priv->nsectors;
if (protsize > protend) {
protsize = protend;
}
/* The final protection range then depends on if the protection region is
* configured top-down or bottom up (assuming CMP=0).
*/
if ((status & STATUS_TB_MASK) != 0) {
protstart = 0x00000000;
protend = protstart + protsize;
} else {
protstart = protend - protsize;
/* protend already computed above */
}
return (address >= protstart && address < protend);
}
/************************************************************************************
* Name: n25qxxx_command_address
************************************************************************************/
__ramfunc__ int n25qxxx_command_address(FAR struct qspi_dev_s *qspi, uint8_t cmd,
off_t addr, uint8_t addrlen)
{
struct qspi_cmdinfo_s cmdinfo;
finfo("CMD: %02" PRIx8 " Address: %04jx addrlen=%" PRIx8 "\n", cmd, (intmax_t) addr, addrlen);
cmdinfo.flags = QSPICMD_ADDRESS;
cmdinfo.addrlen = addrlen;
cmdinfo.cmd = cmd;
cmdinfo.buflen = 0;
cmdinfo.addr = addr;
cmdinfo.buffer = NULL;
int rv;
rv = qspi_command(qspi, &cmdinfo);
return rv;
}
-135
View File
@@ -1,135 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/****************************************************************************
* 10-8--2016:
* To simplify the ripple effect on the tools, we will be using
* /dev/serial/by-id/<asterisk>PX4<asterisk> to locate PX4 devices. Therefore
* moving forward all Bootloaders must contain the prefix "PX4 BL "
* in the USBDEVICESTRING
* This Change will be made in an upcoming BL release
****************************************************************************/
/*
* Define usage to configure a bootloader
*
*
* Constant example Usage
* APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed
* BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request
* BOARD_FMUV2
* INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading
* INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading
* USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string
* USBPRODUCTID 0x0011 - PID Should match defconfig
* BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom
* delay provided by an APP FW
* BOARD_TYPE 9 - Must match .prototype boad_id
* _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection
* BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector
* BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector
* BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time.
* (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted
* programmatically
*
* BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing.
* This is to allow sectors to be reserved for app fw usage. That will NOT be erased
* during a FW upgrade.
* The default is 0, and selects the first sector to be erased, as the 0th entry in the
* flash_sectors table. Which is the second physical sector of FLASH in the device.
* The first physical sector of FLASH is used by the bootloader, and is not defined
* in the table.
*
* APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus
* BOOTLOADER_RESERVATION_SIZE will be deducted from
* BOARD_FLASH_SIZE to determine the size of the App FW
* and hence the address space of FLASH to erase and program.
* USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.)
* SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL
*
* * Other defines are somewhat self explanatory.
*/
/* Boot device selection list*/
#define USB0_DEV 0x01
#define SERIAL0_DEV 0x02
#define SERIAL1_DEV 0x04
#define APP_LOAD_ADDRESS 0x08020000
#define BOOTLOADER_DELAY 5000
#define INTERFACE_USB 1
#define INTERFACE_USB_CONFIG "/dev/ttyACM0"
#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS)
//#define USE_VBUS_PULL_DOWN
#define INTERFACE_USART 6
#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 OSC_FREQ 16
#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE
#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_RED // RED
#define BOARD_LED_ON 1
#define BOARD_LED_OFF 0
#define SERIAL_BREAK_DETECT_DISABLED 1
#if !defined(ARCH_SN_MAX_LENGTH)
# define ARCH_SN_MAX_LENGTH 12
#endif
#if !defined(APP_RESERVATION_SIZE)
# define APP_RESERVATION_SIZE 0
#endif
#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE)
# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1
#endif
#if !defined(USB_DATA_ALIGN)
# define USB_DATA_ALIGN
#endif
#ifndef BOOT_DEVICES_SELECTION
# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
#endif
#ifndef BOOT_DEVICES_FILTER_ONUSB
# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
#endif
-39
View File
@@ -1,39 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/i2c_hw_description.h>
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusExternal(1),
initI2CBusExternal(4),
};
-205
View File
@@ -1,205 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file init.c
*
* FMU-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
*/
#include "board_config.h"
#include <syslog.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <arch/board/board.h>
#include "arm_internal.h"
#include <drivers/drv_hrt.h>
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#include <px4_arch/io_timer.h>
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>
#include <mpu.h>
# if defined(FLASH_BASED_PARAMS)
# include <parameters/flashparams/flashfs.h>
#endif
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS
/************************************************************************************
* Name: board_peripheral_reset
*
* Description:
*
************************************************************************************/
__EXPORT void board_peripheral_reset(int ms)
{
UNUSED(ms);
}
/************************************************************************************
* Name: board_on_reset
*
* Description:
* Optionally provided function called on entry to board_system_reset
* It should perform any house keeping prior to the rest.
*
* status - 1 if resetting to boot loader
* 0 if just resetting
*
************************************************************************************/
__EXPORT void board_on_reset(int status)
{
for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i)));
}
if (status >= 0) {
up_mdelay(6);
}
}
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
/* Reset PWM first thing */
board_on_reset(-1);
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */
stm32_spiinitialize();
/* configure USB interfaces */
stm32_usbinitialize();
}
/****************************************************************************
* Name: board_app_initialize
*
* Description:
* Perform application specific initialization. This function is never
* called directly from application code, but only indirectly via the
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
*
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX;
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* Need hrt running before using the ADC */
px4_platform_init();
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
/* initial LED state */
drv_led_start();
led_off(LED_RED);
led_off(LED_BLUE);
if (board_hardfault_init(2, true) != 0) {
led_on(LED_BLUE);
}
#ifdef CONFIG_MMCSD
int ret = stm32_sdio_initialize();
if (ret != OK) {
led_on(LED_BLUE);
return ret;
}
#endif
// TODOinternal flash store parameters
#if defined(FLASH_BASED_PARAMS)
static sector_descriptor_t params_sector_map[] = {
{15, 128 * 1024, 0x081E0000},
{0, 0, 0},
};
/* Initialize the flashfs layer to use heap allocated memory */
int result = parameter_flashfs_init(params_sector_map, NULL, 0);
if (result != OK) {
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
led_on(LED_RED);
}
#endif
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
}
-113
View File
@@ -1,113 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file led.c
*
* LED backend.
*/
#include <px4_platform_common/px4_config.h>
#include <stdbool.h>
#include "chip.h"
#include "stm32_gpio.h"
#include "board_config.h"
#include <nuttx/board.h>
#include <arch/board/board.h>
/*
* Ideally we'd be able to get these from arm_internal.h,
* but since we want to be able to disable the NuttX use
* of leds for system indication at will and there is no
* separate switch, we need to build independent of the
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
__END_DECLS
# define xlat(p) (p)
static uint32_t g_ledmap[] = {
GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN
GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE
GPIO_nLED_RED, // Indexed by BOARD_LED_RED
};
__EXPORT void led_init(void)
{
/* Configure LED GPIOs for output */
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
if (g_ledmap[l] != 0) {
stm32_configgpio(g_ledmap[l]);
}
}
}
static void phy_set_led(int led, bool state)
{
/* Drive Low to switch on */
if (g_ledmap[led] != 0) {
stm32_gpiowrite(g_ledmap[led], !state);
}
}
static bool phy_get_led(int led)
{
/* If Low it is on */
if (g_ledmap[led] != 0) {
return !stm32_gpioread(g_ledmap[led]);
}
return false;
}
__EXPORT void led_on(int led)
{
phy_set_led(xlat(led), true);
}
__EXPORT void led_off(int led)
{
phy_set_led(xlat(led), false);
}
__EXPORT void led_toggle(int led)
{
phy_set_led(xlat(led), !phy_get_led(xlat(led)));
}
-131
View File
@@ -1,131 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2018-2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file manifest.c
*
* This module supplies the interface to the manifest of hardware that is
* optional and dependent on the HW REV and HW VER IDs
*
* The manifest allows the system to know whether a hardware option
* say for example the PX4IO is an no-pop option vs it is broken.
*
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <inttypes.h>
#include <stdbool.h>
#include <syslog.h>
#include "systemlib/px4_macros.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
typedef struct {
uint32_t hw_ver_rev; /* the version and revision */
const px4_hw_mft_item_t *mft; /* The first entry */
uint32_t entries; /* the lenght of the list */
} px4_hw_mft_list_entry_t;
typedef px4_hw_mft_list_entry_t *px4_hw_mft_list_entry;
#define px4_hw_mft_list_uninitialized (px4_hw_mft_list_entry) -1
static const px4_hw_mft_item_t device_unsupported = {0, 0, 0};
// List of components on a specific board configuration
// The index of those components is given by the enum (px4_hw_mft_item_id_t)
// declared in board_common.h
static const px4_hw_mft_item_t hw_mft_list_v0600[] = {
{
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
};
static px4_hw_mft_list_entry_t mft_lists[] = {
{V6U00, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)},
};
/************************************************************************************
* Name: board_query_manifest
*
* Description:
* Optional returns manifest item.
*
* Input Parameters:
* manifest_id - the ID for the manifest item to retrieve
*
* Returned Value:
* 0 - item is not in manifest => assume legacy operations
* pointer to a manifest item
*
************************************************************************************/
__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
{
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
if (mft_lists[i].hw_ver_rev == ver_rev) {
boards_manifest = &mft_lists[i];
break;
}
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
px4_hw_mft_item rv = &device_unsupported;
if (boards_manifest != px4_hw_mft_list_uninitialized &&
id < boards_manifest->entries) {
rv = &boards_manifest->mft[id];
}
return rv;
}
-77
View File
@@ -1,77 +0,0 @@
/****************************************************************************
*
* 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
//TODO:Prepare for NxtDual
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h>
// KiB BS nB
static const px4_mft_device_t spi5 = { // FM25V02A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32)
.bus_type = px4_mft_device_t::SPI,
.devid = SPIDEV_FLASH(0)
};
static const px4_mtd_entry_t fmum_fram = {
.device = &spi5,
.npart = 1,
.partd = {
{
.type = MTD_PARAMETERS,
.path = "/fs/mtd_params",
.nblocks = 32
}
},
};
static const px4_mtd_manifest_t board_mtd_config = {
.nconfigs = 1,
.entries = {
&fmum_fram
}
};
static const px4_mft_entry_s mtd_mft = {
.type = MTD,
.pmft = (void *) &board_mtd_config,
};
static const px4_mft_s mft = {
.nmft = 1,
.mfts = {
&mtd_mft
}
};
const px4_mft_s *board_get_manifest(void)
{
return &mft;
}
-177
View File
@@ -1,177 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <stdbool.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include "chip.h"
#include "board_config.h"
#include "stm32_gpio.h"
#include "stm32_sdmmc.h"
#ifdef CONFIG_MMCSD
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Card detections requires card support and a card detection GPIO */
#define HAVE_NCD 1
#if !defined(GPIO_SDMMC1_NCD)
# undef HAVE_NCD
#endif
/****************************************************************************
* Private Data
****************************************************************************/
static FAR struct sdio_dev_s *sdio_dev;
#ifdef HAVE_NCD
static bool g_sd_inserted = 0xff; /* Impossible value */
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_ncd_interrupt
*
* Description:
* Card detect interrupt handler.
*
****************************************************************************/
#ifdef HAVE_NCD
static int stm32_ncd_interrupt(int irq, FAR void *context)
{
bool present;
present = !stm32_gpioread(GPIO_SDMMC1_NCD);
if (sdio_dev && present != g_sd_inserted) {
sdio_mediachange(sdio_dev, present);
g_sd_inserted = present;
}
return OK;
}
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void)
{
int ret;
#ifdef HAVE_NCD
/* Card detect */
bool cd_status;
/* Configure the card detect GPIO */
stm32_configgpio(GPIO_SDMMC1_NCD);
/* Register an interrupt handler for the card detect pin */
stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt);
#endif
/* Mount the SDIO-based MMC/SD block driver */
/* First, get an instance of the SDIO interface */
finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO);
sdio_dev = sdio_initialize(SDIO_SLOTNO);
if (!sdio_dev) {
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
return -ENODEV;
}
/* Now bind the SDIO interface to the MMC/SD driver */
finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR);
ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev);
if (ret != OK) {
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
return ret;
}
finfo("Successfully bound SDIO to the MMC/SD driver\n");
#ifdef HAVE_NCD
/* Use SD card detect pin to check if a card is g_sd_inserted */
cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD);
finfo("Card detect : %d\n", cd_status);
sdio_mediachange(sdio_dev, cd_status);
#else
/* Assume that the SD card is inserted. What choice do we have? */
sdio_mediachange(sdio_dev, true);
#endif
return OK;
}
#endif /* CONFIG_MMCSD */
-56
View File
@@ -1,56 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/spi_hw_description.h>
#include <drivers/drv_sensor.h>
#include <nuttx/spi/spi.h>
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortA, GPIO::Pin3}, SPI::DRDY{GPIO::PortA, GPIO::Pin1}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortA, GPIO::Pin2}, SPI::DRDY{GPIO::PortA, GPIO::Pin0}),
}),
initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin4})
}),
initSPIBus(SPI::Bus::SPI3, {
// not in use, future development
}),
initSPIBus(SPI::Bus::SPI4, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortE, GPIO::Pin3}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortC, GPIO::Pin13}, SPI::DRDY{GPIO::PortE, GPIO::Pin4}),
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
@@ -1,56 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/io_timer_hw_description.h>
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer1, DMA{DMA::Index1}),
initIOTimer(Timer::Timer2, DMA{DMA::Index1}),
initIOTimer(Timer::Timer3, DMA{DMA::Index1}),
// initIOTimer(Timer::Timer2),
// initIOTimer(Timer::Timer3),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}),
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}),
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}),
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}),
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel3}, {GPIO::PortB, GPIO::Pin10}),
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortB, GPIO::Pin11}),
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}),
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}),
};
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
initIOTimerChannelMapping(io_timers, timer_io_channels);
-78
View File
@@ -1,78 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file usb.c
*
* Board-specific USB functions.
*/
#include "board_config.h"
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
#include <stm32_otg.h>
#include <debug.h>
/************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the board.
*
************************************************************************************/
__EXPORT void stm32_usbinitialize(void)
{
/* The OTG FS has an internal soft pull-up */
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
#ifdef CONFIG_STM32H7_OTGFS
stm32_configgpio(GPIO_OTGFS_VBUS);
#endif
}
/************************************************************************************
* Name: stm32_usbsuspend
*
* Description:
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
* used. This function is called whenever the USB enters or leaves suspend mode.
* This is an opportunity for the board logic to shutdown clocks, power, etc.
* while the USB is suspended.
*
************************************************************************************/
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}
-3
View File
@@ -1,3 +0,0 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROMFSROOT=""
-105
View File
@@ -1,105 +0,0 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS1"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_COMMON_BAROMETERS=y
CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6500=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_DRIVERS_BAROMETER_BMP388=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PWM_OUT_SIM=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_ROBOCLAW=y
CONFIG_DRIVERS_RPM=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
#CONFIG_DRIVERS_UAVCAN=y
#CONFIG_BOARD_UAVCAN_INTERFACES=1
#CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL=y
CONFIG_MODULES_FW_RATE_CONTROL=y
# CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=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
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
#CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PWM=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=y
-13
View File
@@ -1,13 +0,0 @@
{
"board_id": 1013,
"magic": "PX4FWv1",
"description": "Firmware for the MatekH743-slim board",
"image": "",
"build_time": 0,
"summary": "MatekH743-mini",
"version": "0.1",
"image_size": 0,
"image_maxsize": 1966080,
"git_identity": "",
"board_revision": 0
}
@@ -1,6 +0,0 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default SYS_HAS_MAG 0
param set-default IMU_GYRO_RATEMAX 2000
-13
View File
@@ -1,13 +0,0 @@
#!/bin/sh
#
# board specific extras init
#------------------------------------------------------------------------------
# NxtV1 does not have OSD
# if ! param compare OSD_ATXXXX_CFG 0
# then
# atxxxx start -s
# fi
# DShot telemetry is always on UART7
# dshot telemetry /dev/ttyS5
-16
View File
@@ -1,16 +0,0 @@
#!/bin/sh
#
# board specific sensors init
#------------------------------------------------------------------------------
board_adc start
# # Internal SPI bus ICM24688P
icm42688p -R 0 -s start
# # Internal SPI bus BMI088 accel/gyro
bmi088 -A -R 0 -s start
bmi088 -G -R 0 -s start
# internal baro
bmp388 -I -a 0x76 start
-17
View File
@@ -1,17 +0,0 @@
#
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
config BOARD_HAS_PROBES
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
default y
---help---
This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers.
config BOARD_USE_PROBES
bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11"
default n
depends on BOARD_HAS_PROBES
---help---
Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers.
@@ -1,92 +0,0 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DEV_CONSOLE is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_SPI_EXCHANGE is not set
# CONFIG_STM32H7_SYSCFG is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/hkust/nxt-v1/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743VI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=768
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_INITTHREAD_PRIORITY=254
CONFIG_BOARD_LATE_INITIALIZE=y
CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x004b
CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
#TODOally for VENDOR ID in the future
CONFIG_CDCACM_VENDORID=0x3162
CONFIG_CDCACM_VENDORSTR="Matek"
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=y
CONFIG_DEFAULT_SMALL=y
CONFIG_EXPERIMENTAL=y
CONFIG_FDCLONE_DISABLE=y
CONFIG_FDCLONE_STDIO=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_INIT_ENTRYPOINT="bootloader_main"
CONFIG_INIT_STACKSIZE=3194
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SPI=y
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=32
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_USART3=y
CONFIG_SYSTEMTICK_HOOK=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGINT_CHAR=0x03
CONFIG_TTY_SIGTSTP=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_TXBUFSIZE=300
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
@@ -1,484 +0,0 @@
/************************************************************************************
* nuttx-configs/px4_fmu-v6u/include/board.h
*
* Copyright (C) 2016-2019 Gregory Nutt. All rights reserved.
* Authors: David Sidrane <david.sidrane@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include "board_dma_map.h"
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
#include "stm32_rcc.h"
#include "stm32_sdmmc.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* The MatekH743-Slim board provides the following clock sources:
*
* X1: 16 MHz crystal for HSE
*
* So we have these clock source available within the STM32
*
* HSI: 16 MHz RC factory-trimmed
* HSE: 16 MHz crystal for HSE
*/
#define STM32_BOARD_XTAL 16000000ul
#define STM32_HSI_FREQUENCY 16000000ul
#define STM32_LSI_FREQUENCY 32000
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
#define STM32_LSE_FREQUENCY 32768
/* Main PLL Configuration.
*
* PLL source is HSE = 16,000,000
*
* PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN
* Subject to:
*
* 1 <= PLLM <= 63
* 4 <= PLLN <= 512
* 150 MHz <= PLL_VCOL <= 420MHz
* 192 MHz <= PLL_VCOH <= 836MHz
*
* SYSCLK = PLL_VCO / PLLP
* CPUCLK = SYSCLK / D1CPRE
* Subject to
*
* PLLP1 = {2, 4, 6, 8, ..., 128}
* PLLP2,3 = {2, 3, 4, ..., 128}
* CPUCLK <= 480 MHz
*/
#define STM32_BOARD_USEHSE
#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE
/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR
*
* PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz
*
* PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz
* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz
*/
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \
RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP1EN | \
RCC_PLLCFGR_DIVQ1EN | \
RCC_PLLCFGR_DIVR1EN)
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1)
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60)
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4)
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8)
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60)
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4)
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8)
/* PLL2 */
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \
RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVP2EN | \
RCC_PLLCFGR_DIVQ2EN | \
RCC_PLLCFGR_DIVR2EN)
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4)
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48)
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2)
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2)
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2)
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48)
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
/* PLL3 */
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \
RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \
RCC_PLLCFGR_DIVQ3EN)
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4)
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48)
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2)
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4)
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2)
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48)
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4)
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
/* SYSCLK = PLL1P = 480MHz
* CPUCLK = SYSCLK / 1 = 480 MHz
*/
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1)
/* Configure Clock Assignments */
/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max)
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240
*/
#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */
#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */
#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */
#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */
#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */
#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */
#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* Timer clock frequencies */
/* Timers driven from APB1 will be twice PCLK1 */
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
/* Timers driven from APB2 will be twice PCLK2 */
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY)
/* Kernel Clock Configuration
*
* Note: look at Table 54 in ST Manual
*/
/* I2C123 clock source */
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI
/* I2C4 clock source */
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI
/* SPI123 clock source */
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2
/* SPI45 clock source */
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2
/* SPI6 clock source */
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2
/* USB 1 and 2 clock source */
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3
/* ADC 1 2 3 clock source */
#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2
/* FDCAN 1 clock source */
// #define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */
#define STM32_FDCANCLK STM32_HSE_FREQUENCY
/* FLASH wait states
*
* ------------ ---------- -----------
* Vcore MAX ACLK WAIT STATES
* ------------ ---------- -----------
* 1.15-1.26 V 70 MHz 0
* (VOS1 level) 140 MHz 1
* 210 MHz 2
* 1.05-1.15 V 55 MHz 0
* (VOS2 level) 110 MHz 1
* 165 MHz 2
* 220 MHz 3
* 0.95-1.05 V 45 MHz 0
* (VOS3 level) 90 MHz 1
* 135 MHz 2
* 180 MHz 3
* 225 MHz 4
* ------------ ---------- -----------
*/
#define BOARD_FLASH_WAITSTATES 2
/* SDMMC definitions ********************************************************/
/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
*/
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
/* LED definitions ******************************************************************/
/* The board has two, LED_GREEN a Green LED and LED_BLUE a Blue LED,
* that can be controlled by software.
*
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.
* The following definitions are used to access individual LEDs.
*/
/* LED index values for use with board_userled() */
#define BOARD_LED1 0
#define BOARD_LED2 1
#define BOARD_LED3 2
#define BOARD_NLEDS 3
#define BOARD_LED_RED BOARD_LED1
#define BOARD_LED_GREEN BOARD_LED2
#define BOARD_LED_BLUE BOARD_LED3
/* LED bits for use with board_userled_all() */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
#define BOARD_LED2_BIT (1 << BOARD_LED2)
#define BOARD_LED3_BIT (1 << BOARD_LED3)
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
* events as follows:
*
*
* SYMBOL Meaning LED state
* Red Green Blue
* ---------------------- -------------------------- ------ ------ ----*/
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */
/* Thus if the Green LED is statically on, NuttX has successfully booted and
* is, apparently, running normally. If the Red LED is flashing at
* approximately 2Hz, then a fatal error has been detected and the system
* has halted.
*/
/* Alternate function pin selections ************************************************/
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PBA10 */
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */
#define GPIO_USART1_CK GPIO_USART1_CK /* PB6 */
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART2_CK GPIO_USART2_CK_2 /* PD7 */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_USART3_CK GPIO_USART3_CK_3 /* PD10 */
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */
#define GPIO_UART5_RX GPIO_UART5_RX_1 /* PB12 */
#define GPIO_UART5_TX GPIO_UART5_TX_1 /* PB13 */
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
/* SPI
*
*/
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 /* PA7 */
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2 /* PC2 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_2 /* PC1 */
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_5) /* PD3 */
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_4 /* PB5 */
#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PC10 */
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE5 */
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PB6 */
#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_1) /* PE12 */
/* I2C
*
*
*/
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 /* PB7 */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7)
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11)
/* SDMMC1
*
* SDMMC1_D0 PC8
* SDMMC1_D1 PC9
* SDMMC1_D2 PC10
* SDMMC1_D3 PC11
* SDMMC1_CK PC12
* SDMMC1_CMD PD2
*/
// #define GPIO_SDMMC1_D0 GPIO_SDMMC1_D0 /* PC8 */
// #define GPIO_SDMMC1_D1 GPIO_SDMMC1_D1 /* PC9 */
// #define GPIO_SDMMC1_D2 GPIO_SDMMC1_D2 /* PC10 */
// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3 /* PC11 */
// #define GPIO_SDMMC1_CK GPIO_SDMMC1_CK /* PC12 */
// #define GPIO_SDMMC1_CMD GPIO_SDMMC1_CMD /* PD2 */
/* USB
*
* OTG_FS_DM PA11
* OTG_FS_DP PA12
* VBUS PA9
*/
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
#if defined(CONFIG_BOARD_USE_PROBES)
# include "stm32_gpio.h"
# define PROBE_N(n) (1<<((n)-1))
# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */
# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */
# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */
# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */
# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \
if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \
if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \
} while(0)
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
#else
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)
#endif
#endif /*__NUTTX_CONFIG_MATEKH743SLIM_INCLUDE_BOARD_H */
@@ -1,62 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
// DMAMUX2
#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_0 /* DMA1:61 */
#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_0 /* DMA1:62 */
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* BDMA:11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* BDMA:12 */
//TODO: UART DMA test
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_1 /*DMA2:41*/
#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_1 /*DMA2:42*/
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* DMA2:43 */
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* DMA2:44 */
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* DMA2:45 */
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* DMA2:46 */
#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 */
#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 */
#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_0 /* DMA1:65 */
#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5RX_0 /* DMA1:66 */
@@ -1,272 +0,0 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_ENVIRON is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_DISABLE_PTHREAD is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_CAT is not set
# CONFIG_NSH_DISABLE_CD is not set
# CONFIG_NSH_DISABLE_CP is not set
# CONFIG_NSH_DISABLE_DATE is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_ECHO is not set
# CONFIG_NSH_DISABLE_ENV is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_EXPORT is not set
# CONFIG_NSH_DISABLE_FREE is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_HELP is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_KILL is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_LS is not set
# CONFIG_NSH_DISABLE_MKDIR is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_MOUNT is not set
# CONFIG_NSH_DISABLE_MV is not set
# CONFIG_NSH_DISABLE_PRINTF is not set
# CONFIG_NSH_DISABLE_PS is not set
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
# CONFIG_NSH_DISABLE_PWD is not set
# CONFIG_NSH_DISABLE_RM is not set
# CONFIG_NSH_DISABLE_RMDIR is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_SET is not set
# CONFIG_NSH_DISABLE_SLEEP is not set
# CONFIG_NSH_DISABLE_SOURCE is not set
# CONFIG_NSH_DISABLE_TEST is not set
# CONFIG_NSH_DISABLE_TIME is not set
# CONFIG_NSH_DISABLE_UMOUNT is not set
# CONFIG_NSH_DISABLE_UNSET is not set
# CONFIG_NSH_DISABLE_USLEEP is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/hkust/nxt-v1/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743VI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=768
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU_EARLY_RESET=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_ASSERT_RESET_VALUE=0
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0036
CONFIG_CDCACM_PRODUCTSTR="HKUST UAV NxtPX4"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x1B8C
CONFIG_CDCACM_VENDORSTR="Matek"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_MEMFAULT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEBUG_TCBINFO=n
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_IOB_NBUFFERS=24
CONFIG_IOB_NCHAINS=24
CONFIG_INIT_ENTRYPOINT="nsh_main"
CONFIG_INIT_STACKSIZE=3194
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_MAX_EXITFUNS=1
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_IOB=y
CONFIG_MM_REGIONS=4
# Avaible in Dual Version
# CONFIG_MTD=y
# CONFIG_MTD_BYTE_WRITE=y
# CONFIG_MTD_PARTITION=y
# CONFIG_MTD_PROGMEM=y
# CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_OTG_ID_GPIO_DISABLE=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_SETSPEED=y
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_READLINE_TABCOMPLETION=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SIG_SIGWORK=4
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_STM32H7_ADC1=y
CONFIG_STM32H7_ADC2=y
CONFIG_STM32H7_ADC3=y #should always enable otherwsie got ADC timeout error this is for tempreature compenstae
CONFIG_STM32H7_BBSRAM=y
CONFIG_STM32H7_BBSRAM_FILES=5
CONFIG_STM32H7_BDMA=y
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_FLASH_OVERRIDE_I=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C2=y
CONFIG_STM32H7_I2C_DYNTIMEO=y
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_RTC=y
CONFIG_STM32H7_RTC_HSECLOCK=y
CONFIG_STM32H7_RTC_MAGIC_REG=1
CONFIG_STM32H7_SAVE_CRASHDUMP=y
CONFIG_STM32H7_SDMMC1=y
CONFIG_STM32H7_SDMMC1_DMA=y
CONFIG_STM32H7_SDMMC1_DMA_BUFFER=1024
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI2_DMA=y
CONFIG_STM32H7_SPI2_DMA_BUFFER=4096
CONFIG_STM32H7_SPI3=y
CONFIG_STM32H7_SPI3_DMA=y
CONFIG_STM32H7_SPI3_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
CONFIG_STM32H7_SPI_DMATHRESHOLD=8
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_TIM5=y
CONFIG_STM32H7_TIM8=y
CONFIG_STM32H7_USART1=y #ttyS0
CONFIG_STM32H7_USART2=y #ttyS1
CONFIG_STM32H7_USART3=y #ttyS2
CONFIG_STM32H7_UART4=y #ttyS3
CONFIG_STM32H7_UART5=y #ttyS4
CONFIG_STM32H7_UART7=y #ttyS5
CONFIG_STM32H7_USART_BREAKS=y
CONFIG_STM32H7_USART_INVERT=y
CONFIG_STM32H7_USART_SINGLEWIRE=y
CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=3000
CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=180
CONFIG_USART3_SERIAL_CONSOLE=y
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_UART4_BAUD=921600
CONFIG_UART4_RXBUFSIZE=3000
CONFIG_UART4_TXBUFSIZE=1200
CONFIG_UART5_BAUD=57600
CONFIG_UART5_RXBUFSIZE=600
CONFIG_UART5_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_TXBUFSIZE=3000
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y
CONFIG_WQUEUE_NOTIFIER=y
@@ -1,213 +0,0 @@
/****************************************************************************
* scripts/script.ld
*
* Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory.
* The flash memory is partitioned into a User Flash memory and a System
* Flash memory. Each of these memories has two banks:
*
* 1) User Flash memory:
*
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each
*
* 2) System Flash memory:
*
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector
*
* 3) User option bytes for user configuration, only in Bank 1.
*
* In the STM32H743II, two different boot spaces can be selected through
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
* BOOT_ADD1 option bytes:
*
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
* ST programmed value: Flash memory at 0x0800:0000
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
* ST programmed value: System bootloader at 0x1FF0:0000
*
* The Durandal has a Swtich on board, the BOOT0 pin is at ground so by default,
* the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is
* drepresed, then the boot will be from 0x1FF0:0000
*
* The STM32H743ZI also has 1024Kb of data SRAM.
* SRAM is split up into several blocks and into three power domains:
*
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus
*
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000
*
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit
* DTCM ports. The DTCM-RAM could be used for critical real-time
* data, such as interrupt service routines or stack / heap memory.
* Both DTCM-RAMs can be used in parallel (for load/store operations)
* thanks to the Cortex-M7 dual issue capability.
*
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000
*
* This RAM is connected to ITCM 64-bit interface designed for
* execution of critical real-times routines by the CPU.
*
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA
* through D1 domain AXI bus matrix
*
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000
*
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA
* through D2 domain AHB bus matrix
*
* 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000
*
* SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000
*
* 4) AHB SRAM (D3 domain) accessible by most of system masters
* through D3 domain AHB bus matrix
*
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address range.
*/
MEMORY
{
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K
dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K
sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K
sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K
sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K
sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K
bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
EXTERN(_bootdelay_signature)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(32);
/*
This signature provides the bootloader with a way to delay booting
*/
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}
@@ -1,228 +0,0 @@
/****************************************************************************
* scripts/script.ld
*
* Copyright (C) 2020 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The board uses an STM32H743II and has 2048Kb of main FLASH memory.
* The flash memory is partitioned into a User Flash memory and a System
* Flash memory. Each of these memories has two banks:
*
* 1) User Flash memory:
*
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each
*
* 2) System Flash memory:
*
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector
*
* 3) User option bytes for user configuration, only in Bank 1.
*
* In the STM32H743II, two different boot spaces can be selected through
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
* BOOT_ADD1 option bytes:
*
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
* ST programmed value: Flash memory at 0x0800:0000
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
* ST programmed value: System bootloader at 0x1FF0:0000
*
* There's a switch on board, the BOOT0 pin is at ground so by default,
* the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is
* drepresed, then the boot will be from 0x1FF0:0000
*
* The STM32H743ZI also has 1024Kb of data SRAM.
* SRAM is split up into several blocks and into three power domains:
*
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus
*
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000
*
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit
* DTCM ports. The DTCM-RAM could be used for critical real-time
* data, such as interrupt service routines or stack / heap memory.
* Both DTCM-RAMs can be used in parallel (for load/store operations)
* thanks to the Cortex-M7 dual issue capability.
*
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000
*
* This RAM is connected to ITCM 64-bit interface designed for
* execution of critical real-times routines by the CPU.
*
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA
* through D1 domain AXI bus matrix
*
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000
*
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA
* through D2 domain AHB bus matrix
*
* 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000
*
* SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000
*
* 4) AHB SRAM (D3 domain) accessible by most of system masters
* through D3 domain AHB bus matrix
*
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address range.
*/
MEMORY
{
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */
SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */
SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */
SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */
BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
EXTERN(_bootdelay_signature)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(32);
/*
This signature provides the bootloader with a way to delay booting
*/
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > FLASH
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > FLASH
.ARM.extab : {
*(.ARM.extab*)
} > FLASH
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > FLASH
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
/* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */
. = ALIGN(16);
FILL(0xffff)
. += 16;
} > AXI_SRAM AT > FLASH = 0xffff
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > AXI_SRAM
/* Emit the the D3 power domain section for locating BDMA data */
.sram4_reserve (NOLOAD) :
{
*(.sram4)
. = ALIGN(4);
_sram4_heap_start = ABSOLUTE(.);
} > SRAM4
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}
-68
View File
@@ -1,68 +0,0 @@
############################################################################
#
# Copyright (c) 2021 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
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
add_library(drivers_board
bootloader_main.c
usb.c
)
target_link_libraries(drivers_board
PRIVATE
nuttx_arch
nuttx_drivers
bootloader
)
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common)
else()
add_library(drivers_board
i2c.cpp
init.c
led.c
sdio.c
spi.cpp
timer_config.cpp
usb.c
)
# add_dependencies(drivers_board arch_board_hw_info)
target_link_libraries(drivers_board
PRIVATE
arch_io_pins
arch_spi
arch_board_hw_info
drivers__led
nuttx_arch
nuttx_drivers
px4_layer
)
endif()
-227
View File
@@ -1,227 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file board_config.h
*
* Board internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32_gpio.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
// #define FLASH_BASED_PARAMS
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */
# define GPIO_nLED_RED /* PC6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN6)
# define GPIO_nLED_GREEN /* PB14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14)
# define GPIO_nLED_BLUE /* PB15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
# define BOARD_HAS_CONTROL_STATUS_LEDS 1
# define BOARD_OVERLOAD_LED LED_RED
# define BOARD_ARMED_STATE_LED LED_BLUE
/* I2C busses */
/* Devices on the onboard buses.
*
* Note that these are unshifted addresses.
*/
// #define PX4_I2C_OBDEV_SE050 0x48
#define GPIO_I2C1_DRDY1_BMP388 /* PB9 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN9)
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that
* can be used by the Px4 Firmware in the adc driver
*/
/* ADC defines to be used in sensors.cpp to read from a particular channel */
#define SYSTEM_ADC_BASE STM32_ADC1_BASE
#define ADC12_CH(n) (n)
#define PX4_ADC_GPIO \
/* PB0 */ GPIO_ADC12_INP5, \
/* PB1 */ GPIO_ADC12_INP9
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_BATTERY_VOLTAGE_CHANNEL ADC12_CH(9)
#define ADC_BATTERY_CURRENT_CHANNEL ADC12_CH(5)
#define ADC_CHANNELS \
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY_CURRENT_CHANNEL))
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* Define Battery 1 Voltage Divider and A per V
*/
// #define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */
// #define BOARD_BATTERY1_A_PER_V (40.0f)
// #define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */
/* PWM
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 8
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/* Spare GPIO */
#define GPIO_PD4 /* PD4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN4)
#define GPIO_PC13 /* PC13 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN13)
#define GPIO_PH1 /* PH1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTH|GPIO_PIN1)
/* Tone alarm output */
#define TONE_ALARM_TIMER 1 /* Timer 3 */
#define TONE_ALARM_CHANNEL 1 /* PC7 GPIO_TIM3_CH2 */
/*NC can be modified with Spare GPIO then connected with hardware */
#define GPIO_BUZZER_1 /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
#define GPIO_TONE_ALARM GPIO_BUZZER_1
/* USB OTG FS
*
* PE2 OTG_FS_VBUS VBUS sensing
*/
#define GPIO_OTGFS_VBUS /* PA15 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN15)
#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS))
/* High-resolution timer */
#define HRT_TIMER 8 /* use timer1 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
/* SD card bringup does not work if performed on the IDLE thread because it
* will cause waiting. Use either:
*
* CONFIG_LIB_BOARDCTL=y, OR
* CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y
*/
#define SDIO_SLOTNO 0 /* Only one slot */
#define SDIO_MINOR 0
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \
!defined(CONFIG_BOARD_INITTHREAD)
# warning SDIO initialization cannot be perfomed on the IDLE thread
#endif
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_TONE_ALARM_IDLE, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_NUM_IO_TIMERS 5
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void);
/****************************************************************************************************
* Name: stm32_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the board.
*
****************************************************************************************************/
extern void stm32_spiinitialize(void);
extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS
-75
View File
@@ -1,75 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file bootloader_main.c
*
* FMU-specific early startup code for bootloader
*/
#include "board_config.h"
#include "bl.h"
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <chip.h>
#include <stm32_uart.h>
#include <arch/board/board.h>
#include "arm_internal.h"
#include <px4_platform_common/init.h>
extern int sercon_main(int c, char **argv);
__EXPORT void board_on_reset(int status) {}
__EXPORT void stm32_boardinitialize(void)
{
/* configure USB interfaces */
stm32_usbinitialize();
}
__EXPORT int board_app_initialize(uintptr_t arg)
{
return 0;
}
void board_late_initialize(void)
{
sercon_main(0, NULL);
}
extern void sys_tick_handler(void);
void board_timerhook(void)
{
sys_tick_handler();
}
-135
View File
@@ -1,135 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/****************************************************************************
* 10-8--2016:
* To simplify the ripple effect on the tools, we will be using
* /dev/serial/by-id/<asterisk>PX4<asterisk> to locate PX4 devices. Therefore
* moving forward all Bootloaders must contain the prefix "PX4 BL "
* in the USBDEVICESTRING
* This Change will be made in an upcoming BL release
****************************************************************************/
/*
* Define usage to configure a bootloader
*
*
* Constant example Usage
* APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed
* BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request
* BOARD_FMUV2
* INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading
* INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading
* USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string
* USBPRODUCTID 0x0011 - PID Should match defconfig
* BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom
* delay provided by an APP FW
* BOARD_TYPE 9 - Must match .prototype boad_id
* _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection
* BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector
* BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector
* BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time.
* (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted
* programmatically
*
* BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing.
* This is to allow sectors to be reserved for app fw usage. That will NOT be erased
* during a FW upgrade.
* The default is 0, and selects the first sector to be erased, as the 0th entry in the
* flash_sectors table. Which is the second physical sector of FLASH in the device.
* The first physical sector of FLASH is used by the bootloader, and is not defined
* in the table.
*
* APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus
* BOOTLOADER_RESERVATION_SIZE will be deducted from
* BOARD_FLASH_SIZE to determine the size of the App FW
* and hence the address space of FLASH to erase and program.
* USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.)
* SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL
*
* * Other defines are somewhat self explanatory.
*/
/* Boot device selection list*/
#define USB0_DEV 0x01
#define SERIAL0_DEV 0x02
#define SERIAL1_DEV 0x04
#define APP_LOAD_ADDRESS 0x08020000
#define BOOTLOADER_DELAY 5000
#define INTERFACE_USB 1
#define INTERFACE_USB_CONFIG "/dev/ttyACM0"
#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS)
//#define USE_VBUS_PULL_DOWN
#define INTERFACE_USART 1
#define INTERFACE_USART_CONFIG "/dev/ttyS0,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 OSC_FREQ 16
#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE
#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_RED // RED
#define BOARD_LED_ON 1
#define BOARD_LED_OFF 0
#define SERIAL_BREAK_DETECT_DISABLED 1
#if !defined(ARCH_SN_MAX_LENGTH)
# define ARCH_SN_MAX_LENGTH 12
#endif
#if !defined(APP_RESERVATION_SIZE)
# define APP_RESERVATION_SIZE 0
#endif
#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE)
# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1
#endif
#if !defined(USB_DATA_ALIGN)
# define USB_DATA_ALIGN
#endif
#ifndef BOOT_DEVICES_SELECTION
# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
#endif
#ifndef BOOT_DEVICES_FILTER_ONUSB
# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
#endif
-39
View File
@@ -1,39 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/i2c_hw_description.h>
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusInternal(1),
initI2CBusExternal(2),
};
-205
View File
@@ -1,205 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file init.c
*
* FMU-specific early startup code. This file implements the
* board_app_initialize() function that is called early by nsh during startup.
*
* Code here is run before the rcS script is invoked; it should start required
* subsystems and perform board-specific initialisation.
*/
#include "board_config.h"
#include <syslog.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <arch/board/board.h>
#include "arm_internal.h"
#include <drivers/drv_hrt.h>
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#include <px4_arch/io_timer.h>
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>
#include <mpu.h>
# if defined(FLASH_BASED_PARAMS)
# include <parameters/flashparams/flashfs.h>
#endif
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS
/************************************************************************************
* Name: board_peripheral_reset
*
* Description:
*
************************************************************************************/
__EXPORT void board_peripheral_reset(int ms)
{
UNUSED(ms);
}
/************************************************************************************
* Name: board_on_reset
*
* Description:
* Optionally provided function called on entry to board_system_reset
* It should perform any house keeping prior to the rest.
*
* status - 1 if resetting to boot loader
* 0 if just resetting
*
************************************************************************************/
__EXPORT void board_on_reset(int status)
{
for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i)));
}
if (status >= 0) {
up_mdelay(6);
}
}
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
/* Reset PWM first thing */
board_on_reset(-1);
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */
stm32_spiinitialize();
/* configure USB interfaces */
stm32_usbinitialize();
}
/****************************************************************************
* Name: board_app_initialize
*
* Description:
* Perform application specific initialization. This function is never
* called directly from application code, but only indirectly via the
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
*
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX;
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* Need hrt running before using the ADC */
px4_platform_init();
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
/* initial LED state */
drv_led_start();
led_off(LED_RED);
led_off(LED_BLUE);
if (board_hardfault_init(2, true) != 0) {
led_on(LED_BLUE);
}
#ifdef CONFIG_MMCSD
int ret = stm32_sdio_initialize();
if (ret != OK) {
led_on(LED_BLUE);
return ret;
}
#endif
// TODOinternal flash store parameters
#if defined(FLASH_BASED_PARAMS)
static sector_descriptor_t params_sector_map[] = {
{15, 128 * 1024, 0x081E0000},
{0, 0, 0},
};
/* Initialize the flashfs layer to use heap allocated memory */
int result = parameter_flashfs_init(params_sector_map, NULL, 0);
if (result != OK) {
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
led_on(LED_RED);
}
#endif
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
}
-113
View File
@@ -1,113 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file led.c
*
* LED backend.
*/
#include <px4_platform_common/px4_config.h>
#include <stdbool.h>
#include "chip.h"
#include "stm32_gpio.h"
#include "board_config.h"
#include <nuttx/board.h>
#include <arch/board/board.h>
/*
* Ideally we'd be able to get these from arm_internal.h,
* but since we want to be able to disable the NuttX use
* of leds for system indication at will and there is no
* separate switch, we need to build independent of the
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
__END_DECLS
# define xlat(p) (p)
static uint32_t g_ledmap[] = {
GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN
GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE
GPIO_nLED_RED, // Indexed by BOARD_LED_RED
};
__EXPORT void led_init(void)
{
/* Configure LED GPIOs for output */
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
if (g_ledmap[l] != 0) {
stm32_configgpio(g_ledmap[l]);
}
}
}
static void phy_set_led(int led, bool state)
{
/* Drive Low to switch on */
if (g_ledmap[led] != 0) {
stm32_gpiowrite(g_ledmap[led], !state);
}
}
static bool phy_get_led(int led)
{
/* If Low it is on */
if (g_ledmap[led] != 0) {
return !stm32_gpioread(g_ledmap[led]);
}
return false;
}
__EXPORT void led_on(int led)
{
phy_set_led(xlat(led), true);
}
__EXPORT void led_off(int led)
{
phy_set_led(xlat(led), false);
}
__EXPORT void led_toggle(int led)
{
phy_set_led(xlat(led), !phy_get_led(xlat(led)));
}
-81
View File
@@ -1,81 +0,0 @@
/****************************************************************************
*
* 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
//TODO:Prepare for NxtDual
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h>
// KiB BS nB
static const px4_mft_device_t spi5 = { // FM25V02A on FMUM 32K 512 X 64
.bus_type = px4_mft_device_t::SPI,
.devid = SPIDEV_FLASH(0)
};
static const px4_mtd_entry_t fmum_fram = {
.device = &spi5,
.npart = 2,
.partd = {
{
.type = MTD_PARAMETERS,
.path = "/fs/mtd_params",
.nblocks = 32
},
{
.type = MTD_WAYPOINTS,
.path = "/fs/mtd_waypoints",
.nblocks = 32
}
},
};
static const px4_mtd_manifest_t board_mtd_config = {
.nconfigs = 1,
.entries = {
&fmum_fram
}
};
static const px4_mft_entry_s mtd_mft = {
.type = MTD,
.pmft = (void *) &board_mtd_config,
};
static const px4_mft_s mft = {
.nmft = 1,
.mfts = &mtd_mft
};
const px4_mft_s *board_get_manifest(void)
{
return &mft;
}
-177
View File
@@ -1,177 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <stdbool.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include "chip.h"
#include "board_config.h"
#include "stm32_gpio.h"
#include "stm32_sdmmc.h"
#ifdef CONFIG_MMCSD
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Card detections requires card support and a card detection GPIO */
#define HAVE_NCD 1
#if !defined(GPIO_SDMMC1_NCD)
# undef HAVE_NCD
#endif
/****************************************************************************
* Private Data
****************************************************************************/
static FAR struct sdio_dev_s *sdio_dev;
#ifdef HAVE_NCD
static bool g_sd_inserted = 0xff; /* Impossible value */
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_ncd_interrupt
*
* Description:
* Card detect interrupt handler.
*
****************************************************************************/
#ifdef HAVE_NCD
static int stm32_ncd_interrupt(int irq, FAR void *context)
{
bool present;
present = !stm32_gpioread(GPIO_SDMMC1_NCD);
if (sdio_dev && present != g_sd_inserted) {
sdio_mediachange(sdio_dev, present);
g_sd_inserted = present;
}
return OK;
}
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void)
{
int ret;
#ifdef HAVE_NCD
/* Card detect */
bool cd_status;
/* Configure the card detect GPIO */
stm32_configgpio(GPIO_SDMMC1_NCD);
/* Register an interrupt handler for the card detect pin */
stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt);
#endif
/* Mount the SDIO-based MMC/SD block driver */
/* First, get an instance of the SDIO interface */
finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO);
sdio_dev = sdio_initialize(SDIO_SLOTNO);
if (!sdio_dev) {
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
return -ENODEV;
}
/* Now bind the SDIO interface to the MMC/SD driver */
finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR);
ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev);
if (ret != OK) {
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
return ret;
}
finfo("Successfully bound SDIO to the MMC/SD driver\n");
#ifdef HAVE_NCD
/* Use SD card detect pin to check if a card is g_sd_inserted */
cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD);
finfo("Card detect : %d\n", cd_status);
sdio_mediachange(sdio_dev, cd_status);
#else
/* Assume that the SD card is inserted. What choice do we have? */
sdio_mediachange(sdio_dev, true);
#endif
return OK;
}
#endif /* CONFIG_MMCSD */
-52
View File
@@ -1,52 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/spi_hw_description.h>
#include <drivers/drv_sensor.h>
#include <nuttx/spi/spi.h>
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_MPU6500, SPI::CS{GPIO::PortC, GPIO::Pin4}, SPI::DRDY{GPIO::PortC, GPIO::Pin5}),
}),
initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortC, GPIO::Pin3}, SPI::DRDY{GPIO::PortA, GPIO::Pin4}),
}),
initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortE, GPIO::Pin3}, SPI::DRDY{GPIO::PortE, GPIO::Pin0}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortE, GPIO::Pin4}, SPI::DRDY{GPIO::PortE, GPIO::Pin1}),
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
-55
View File
@@ -1,55 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_arch/io_timer_hw_description.h>
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer5, DMA{DMA::Index1}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
initIOTimer(Timer::Timer1),
initIOTimer(Timer::Timer3),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}),
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}),
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}),
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}),
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel2}, {GPIO::PortC, GPIO::Pin7}),
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9})
};
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
initIOTimerChannelMapping(io_timers, timer_io_channels);
-78
View File
@@ -1,78 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2021 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file usb.c
*
* Board-specific USB functions.
*/
#include "board_config.h"
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
#include <stm32_otg.h>
#include <debug.h>
/************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the board.
*
************************************************************************************/
__EXPORT void stm32_usbinitialize(void)
{
/* The OTG FS has an internal soft pull-up */
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
#ifdef CONFIG_STM32H7_OTGFS
stm32_configgpio(GPIO_OTGFS_VBUS);
#endif
}
/************************************************************************************
* Name: stm32_usbsuspend
*
* Description:
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
* used. This function is called whenever the USB enters or leaves suspend mode.
* This is an opportunity for the board logic to shutdown clocks, power, etc.
* while the USB is suspended.
*
************************************************************************************/
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}
+1 -1
View File
@@ -43,7 +43,7 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortB, GPIO::Pin12}),
}),
initSPIBus(SPI::Bus::SPI4, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortE, GPIO::Pin4}, SPI::DRDY{GPIO::PortE, GPIO::Pin1}),
initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortE, GPIO::Pin4}, SPI::DRDY{GPIO::PortE, GPIO::Pin1}),
initSPIDevice(DRV_IMU_DEVTYPE_MPU6000, SPI::CS{GPIO::PortE, GPIO::Pin4}, SPI::DRDY{GPIO::PortE, GPIO::Pin1}),
initSPIDevice(DRV_IMU_DEVTYPE_BMI270, SPI::CS{GPIO::PortE, GPIO::Pin4}, SPI::DRDY{GPIO::PortE, GPIO::Pin1}),
}),
Binary file not shown.
+3 -1
View File
@@ -102,7 +102,9 @@
(1 << ADC_RSSI_IN_CHANNEL))
/* Define Battery Voltage Divider and A per V */
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (40.0f)
#define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */
+3 -1
View File
@@ -102,7 +102,9 @@
(1 << ADC_RSSI_IN_CHANNEL))
/* Define Battery Voltage Divider and A per V */
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (40.0f)
#define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */
+1 -2
View File
@@ -24,7 +24,6 @@ CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_CRSF_RC=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
@@ -61,7 +60,7 @@ CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
# CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
@@ -1,5 +0,0 @@
#!/bin/bash
# Run this from the px4 project top level directory
docker run -it --rm --privileged -v `pwd`:/usr/local/workspace px4io/px4-dev-nuttx-focal:2022-08-12
+1 -5
View File
@@ -4,15 +4,13 @@ CONFIG_DRIVERS_ACTUATORS_VOXL_ESC=y
CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP101XX=y
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L1X=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
CONFIG_DRIVERS_RC_CRSF_RC=y
CONFIG_DRIVERS_QSHELL_QURT=y
CONFIG_DRIVERS_VOXL2_IO=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_EKF2=y
@@ -30,6 +28,4 @@ CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_ORB_COMMUNICATOR=y
CONFIG_PARAM_REMOTE=y
+3 -2
View File
@@ -44,10 +44,11 @@ add_library(drivers_board
)
# Add custom drivers for SLPI
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/icm42688p)
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/rc_controller)
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/mavlink_rc_in)
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/spektrum_rc)
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/ghst_rc)
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_hitl)
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/ghst_rc)
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_hitl)
# add_subdirectory(${PX4_BOARD_DIR}/src/drivers/dsp_sbus)
add_subdirectory(${PX4_BOARD_DIR}/src/drivers/elrs_led)
@@ -62,8 +62,6 @@
#include <uORB/topics/vehicle_odometry.h>
#include <uORB/topics/sensor_baro.h>
#include <uORB/topics/esc_status.h>
#include <uORB/topics/distance_sensor.h>
#include <uORB/topics/sensor_optical_flow.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
@@ -90,22 +88,21 @@ static bool _is_running = false;
volatile bool _task_should_exit = false;
static px4_task_t _task_handle = -1;
int _uart_fd = -1;
bool _debug = false;
bool debug = false;
std::string port = "2";
int baudrate = 921600;
const unsigned mode_flag_custom = 1;
const unsigned mode_flag_armed = 128;
bool _send_gps = false;
bool _send_mag = false;
bool _send_distance = false;
uORB::Publication<battery_status_s> _battery_pub{ORB_ID(battery_status)};
uORB::PublicationMulti<sensor_gps_s> _sensor_gps_pub{ORB_ID(sensor_gps)};
uORB::Publication<differential_pressure_s> _differential_pressure_pub{ORB_ID(differential_pressure)};
uORB::Publication<vehicle_odometry_s> _visual_odometry_pub{ORB_ID(vehicle_visual_odometry)};
uORB::Publication<vehicle_odometry_s> _mocap_odometry_pub{ORB_ID(vehicle_mocap_odometry)};
uORB::PublicationMulti<sensor_baro_s> _sensor_baro_pub{ORB_ID(sensor_baro)};
uORB::Publication<esc_status_s> _esc_status_pub{ORB_ID(esc_status)};
uORB::Publication<distance_sensor_s> _distance_sensor_pub{ORB_ID(distance_sensor)};
uORB::Publication<sensor_optical_flow_s> _sensor_optical_flow_pub{ORB_ID(sensor_optical_flow)};
uORB::Subscription _battery_status_sub{ORB_ID(battery_status)};
int32_t _output_functions[actuator_outputs_s::NUM_ACTUATOR_OUTPUTS] {};
@@ -131,42 +128,13 @@ float x_gyro = 0;
float y_gyro = 0;
float z_gyro = 0;
uint64_t gyro_accel_time = 0;
bool _use_software_mav_throttling{false};
// Status counters
uint32_t heartbeat_received_counter = 0;
uint32_t heartbeat_sent_counter = 0;
uint32_t imu_counter = 0;
uint32_t hil_sensor_counter = 0;
uint32_t mag_counter = 0;
uint32_t baro_counter = 0;
uint32_t actuator_sent_counter = 0;
uint32_t odometry_received_counter = 0;
uint32_t odometry_sent_counter = 0;
uint32_t gps_received_counter = 0;
uint32_t gps_sent_counter = 0;
uint32_t distance_received_counter = 0;
uint32_t distance_sent_counter = 0;
uint32_t flow_received_counter = 0;
uint32_t flow_sent_counter = 0;
uint32_t unknown_msg_received_counter = 0;
enum class position_source {GPS, VIO, FLOW, NUM_POSITION_SOURCES};
struct position_source_data_s {
char label[8];
bool send;
bool fail;
uint32_t failure_duration;
uint64_t failure_duration_start;
} position_source_data[(int) position_source::NUM_POSITION_SOURCES] = {
{"GPS", false, false, 0, 0},
{"VIO", false, false, 0, 0},
{"FLOW", false, false, 0, 0}
};
uint64_t first_sensor_msg_timestamp = 0;
uint64_t first_sensor_report_timestamp = 0;
uint64_t last_sensor_report_timestamp = 0;
int heartbeat_counter = 0;
int imu_counter = 0;
int hil_sensor_counter = 0;
int vision_msg_counter = 0;
int gps_counter = 0;
vehicle_status_s _vehicle_status{};
vehicle_control_mode_s _control_mode{};
@@ -176,6 +144,7 @@ battery_status_s _battery_status{};
sensor_accel_fifo_s accel_fifo{};
sensor_gyro_fifo_s gyro_fifo{};
int openPort(const char *dev, speed_t speed);
int closePort();
@@ -184,8 +153,7 @@ int writeResponse(void *buf, size_t len);
int start(int argc, char *argv[]);
int stop();
void print_status();
void clear_status_counters();
int get_status();
bool isOpen() { return _uart_fd >= 0; };
void usage();
@@ -195,65 +163,50 @@ void *send_actuator(void *);
void send_actuator_data();
void handle_message_hil_sensor_dsp(mavlink_message_t *msg);
void handle_message_hil_optical_flow(mavlink_message_t *msg);
void handle_message_distance_sensor(mavlink_message_t *msg);
void handle_message_hil_gps_dsp(mavlink_message_t *msg);
void handle_message_odometry_dsp(mavlink_message_t *msg);
void handle_message_vision_position_estimate_dsp(mavlink_message_t *msg);
void handle_message_command_long_dsp(mavlink_message_t *msg);
void handle_message_dsp(mavlink_message_t *msg);
void actuator_controls_from_outputs_dsp(mavlink_hil_actuator_controls_t *msg);
void send_esc_status(mavlink_hil_actuator_controls_t hil_act_control);
void send_esc_telemetry_dsp(mavlink_hil_actuator_controls_t hil_act_control);
void
handle_message_dsp(mavlink_message_t *msg)
{
switch (msg->msgid) {
case MAVLINK_MSG_ID_HIL_SENSOR:
hil_sensor_counter++;
handle_message_hil_sensor_dsp(msg);
break;
case MAVLINK_MSG_ID_HIL_GPS:
gps_received_counter++;
if (_send_gps) { handle_message_hil_gps_dsp(msg); }
if (position_source_data[(int) position_source::GPS].send) { handle_message_hil_gps_dsp(msg); }
break;
case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
handle_message_vision_position_estimate_dsp(msg);
break;
case MAVLINK_MSG_ID_ODOMETRY:
odometry_received_counter++;
if (position_source_data[(int) position_source::VIO].send) { handle_message_odometry_dsp(msg); }
handle_message_odometry_dsp(msg);
break;
case MAVLINK_MSG_ID_COMMAND_LONG:
handle_message_command_long_dsp(msg);
break;
case MAVLINK_MSG_ID_HEARTBEAT:
heartbeat_received_counter++;
if (_debug) { PX4_INFO("Heartbeat msg received"); }
PX4_DEBUG("Heartbeat msg received");
break;
case MAVLINK_MSG_ID_HIL_OPTICAL_FLOW:
flow_received_counter++;
if (position_source_data[(int) position_source::FLOW].send) { handle_message_hil_optical_flow(msg); }
break;
case MAVLINK_MSG_ID_DISTANCE_SENSOR:
distance_received_counter++;
if (_send_distance) { handle_message_distance_sensor(msg); }
case MAVLINK_MSG_ID_SYSTEM_TIME:
PX4_DEBUG("MAVLINK SYSTEM TIME");
break;
default:
unknown_msg_received_counter++;
if (_debug) { PX4_INFO("Unknown msg ID: %d", msg->msgid); }
PX4_DEBUG("Unknown msg ID: %d", msg->msgid);
break;
}
}
@@ -275,6 +228,7 @@ void send_actuator_data()
bool first_sent = false;
while (true) {
bool controls_updated = false;
(void) orb_check(_vehicle_control_mode_sub_, &controls_updated);
@@ -285,50 +239,45 @@ void send_actuator_data()
bool actuator_updated = false;
(void) orb_check(_actuator_outputs_sub, &actuator_updated);
uint8_t newBuf[512];
uint16_t newBufLen = 0;
mavlink_hil_actuator_controls_t hil_act_control;
actuator_controls_from_outputs_dsp(&hil_act_control);
mavlink_message_t message{};
mavlink_msg_hil_actuator_controls_encode(1, 1, &message, &hil_act_control);
if (actuator_updated) {
orb_copy(ORB_ID(actuator_outputs), _actuator_outputs_sub, &_actuator_outputs);
px4_lockstep_wait_for_components();
if (_actuator_outputs.timestamp > 0) {
mavlink_hil_actuator_controls_t hil_act_control;
actuator_controls_from_outputs_dsp(&hil_act_control);
mavlink_message_t message{};
mavlink_msg_hil_actuator_controls_encode(1, 1, &message, &hil_act_control);
previous_timestamp = _actuator_outputs.timestamp;
previous_uorb_timestamp = _actuator_outputs.timestamp;
uint8_t newBuf[512];
uint16_t newBufLen = 0;
newBufLen = mavlink_msg_to_send_buffer(newBuf, &message);
int writeRetval = writeResponse(&newBuf, newBufLen);
actuator_sent_counter++;
if (_debug) { PX4_INFO("Succesful write of actuator back to jMAVSim: %d at %llu", writeRetval, hrt_absolute_time()); }
PX4_DEBUG("Succesful write of actuator back to jMAVSim: %d at %llu", writeRetval, hrt_absolute_time());
first_sent = true;
send_esc_status(hil_act_control);
send_esc_telemetry_dsp(hil_act_control);
}
} else if (! actuator_updated && first_sent && differential > 4000) {
} else if (!actuator_updated && first_sent && differential > 4000) {
mavlink_hil_actuator_controls_t hil_act_control;
actuator_controls_from_outputs_dsp(&hil_act_control);
previous_timestamp = hrt_absolute_time();
mavlink_message_t message{};
mavlink_msg_hil_actuator_controls_encode(1, 1, &message, &hil_act_control);
uint8_t newBuf[512];
uint16_t newBufLen = 0;
newBufLen = mavlink_msg_to_send_buffer(newBuf, &message);
int writeRetval = writeResponse(&newBuf, newBufLen);
//PX4_INFO("Sending from NOT UPDTE AND TIMEOUT: %i", differential);
actuator_sent_counter++;
if (_debug) { PX4_INFO("Succesful write of actuator back to jMAVSim: %d at %llu", writeRetval, hrt_absolute_time()); }
send_esc_status(hil_act_control);
PX4_DEBUG("Succesful write of actuator back to jMAVSim: %d at %llu", writeRetval, hrt_absolute_time());
send_esc_telemetry_dsp(hil_act_control);
}
differential = hrt_absolute_time() - previous_timestamp;
px4_usleep(1000);
}
}
@@ -338,10 +287,14 @@ void task_main(int argc, char *argv[])
int myoptind = 1;
const char *myoptarg = nullptr;
while ((ch = px4_getopt(argc, argv, "odmghfp:b:", &myoptind, &myoptarg)) != EOF) {
while ((ch = px4_getopt(argc, argv, "vsdcmgp:b:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 's':
_use_software_mav_throttling = true;
break;
case 'd':
_debug = true;
debug = true;
break;
case 'p':
@@ -357,19 +310,7 @@ void task_main(int argc, char *argv[])
break;
case 'g':
position_source_data[(int) position_source::GPS].send = true;
break;
case 'o':
position_source_data[(int) position_source::VIO].send = true;
break;
case 'h':
_send_distance = true;
break;
case 'f':
position_source_data[(int) position_source::FLOW].send = true;
_send_gps = true;
break;
default:
@@ -378,13 +319,11 @@ void task_main(int argc, char *argv[])
}
const char *charport = port.c_str();
(void) openPort(charport, (speed_t) baudrate);
int openRetval = openPort(charport, (speed_t) baudrate);
int open = isOpen();
if ((_debug) && (isOpen())) { PX4_INFO("DSP HITL serial port initialized. Baudrate: %d", baudrate); }
if (! isOpen()) {
PX4_ERR("DSP HITL failed to open serial port");
return;
if (open) {
PX4_ERR("Port is open: %d", openRetval);
}
uint64_t last_heartbeat_timestamp = hrt_absolute_time();
@@ -403,11 +342,14 @@ void task_main(int argc, char *argv[])
pthread_attr_destroy(&sender_thread_attr);
int _vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
PX4_INFO("Got %d from orb_subscribe", _vehicle_status_sub);
_is_running = true;
while (!_task_should_exit) {
uint8_t rx_buf[1024];
//rx_buf[511] = '\0';
uint64_t timestamp = hrt_absolute_time();
@@ -415,8 +357,8 @@ void task_main(int argc, char *argv[])
if (got_first_sensor_msg) {
uint64_t delta_time = timestamp - last_imu_update_timestamp;
if ((imu_counter) && (delta_time > 15000)) {
PX4_WARN("Sending updates at %llu, delta %llu", timestamp, delta_time);
if (delta_time > 15000) {
PX4_ERR("Sending updates at %llu, delta %llu", timestamp, delta_time);
}
uint64_t _px4_gyro_accel_timestamp = hrt_absolute_time();
@@ -454,7 +396,7 @@ void task_main(int argc, char *argv[])
hb_newBufLen = mavlink_msg_to_send_buffer(hb_newBuf, &hb_message);
(void) writeResponse(&hb_newBuf, hb_newBufLen);
last_heartbeat_timestamp = timestamp;
heartbeat_sent_counter++;
heartbeat_counter++;
}
bool vehicle_updated = false;
@@ -474,7 +416,7 @@ void task_main(int argc, char *argv[])
_is_running = false;
}
void send_esc_status(mavlink_hil_actuator_controls_t hil_act_control)
void send_esc_telemetry_dsp(mavlink_hil_actuator_controls_t hil_act_control)
{
esc_status_s esc_status{};
esc_status.timestamp = hrt_absolute_time();
@@ -506,13 +448,17 @@ void send_esc_status(mavlink_hil_actuator_controls_t hil_act_control)
_esc_status_pub.publish(esc_status);
}
void
handle_message_command_long_dsp(mavlink_message_t *msg)
{
/* command */
mavlink_command_long_t cmd_mavlink;
mavlink_msg_command_long_decode(msg, &cmd_mavlink);
if (_debug) { PX4_INFO("Value of command_long.command: %d", cmd_mavlink.command); }
if (debug) {
PX4_INFO("Value of command_long.command: %d", cmd_mavlink.command);
}
mavlink_command_ack_t ack = {};
ack.result = MAV_RESULT_UNSUPPORTED;
@@ -524,140 +470,46 @@ handle_message_command_long_dsp(mavlink_message_t *msg)
uint16_t acknewBufLen = 0;
acknewBufLen = mavlink_msg_to_send_buffer(acknewBuf, &ack_message);
int writeRetval = writeResponse(&acknewBuf, acknewBufLen);
if (_debug) { PX4_INFO("Succesful write of ACK back over UART: %d at %llu", writeRetval, hrt_absolute_time()); }
PX4_INFO("Succesful write of ACK back over UART: %d at %llu", writeRetval, hrt_absolute_time());
}
int flow_debug_counter = 0;
void
handle_message_hil_optical_flow(mavlink_message_t *msg)
handle_message_vision_position_estimate_dsp(mavlink_message_t *msg)
{
mavlink_hil_optical_flow_t flow;
mavlink_msg_hil_optical_flow_decode(msg, &flow);
mavlink_vision_position_estimate_t vpe;
mavlink_msg_vision_position_estimate_decode(msg, &vpe);
if ((_debug) && (!(flow_debug_counter % 10))) {
PX4_INFO("optflow: time: %llu, quality %d", flow.time_usec, (int) flow.quality);
PX4_INFO("optflow: x: %.2f y: %.2f", (double) flow.integrated_x, (double) flow.integrated_y);
}
// fill vehicle_odometry from Mavlink VISION_POSITION_ESTIMATE
vehicle_odometry_s odom{};
uint64_t timestamp = hrt_absolute_time();
odom.timestamp_sample = timestamp;
flow_debug_counter++;
odom.pose_frame = vehicle_odometry_s::POSE_FRAME_NED;
odom.position[0] = vpe.x;
odom.position[1] = vpe.y;
odom.position[2] = vpe.z;
device::Device::DeviceId device_id;
device_id.devid_s.bus_type = device::Device::DeviceBusType::DeviceBusType_MAVLINK;
device_id.devid_s.bus = 1;
device_id.devid_s.address = msg->sysid;
device_id.devid_s.devtype = DRV_FLOW_DEVTYPE_SIM;
const matrix::Quatf q(matrix::Eulerf(vpe.roll, vpe.pitch, vpe.yaw));
q.copyTo(odom.q);
sensor_optical_flow_s sensor_optical_flow{};
// VISION_POSITION_ESTIMATE covariance
// Row-major representation of pose 6x6 cross-covariance matrix upper right triangle
// (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.).
// If unknown, assign NaN value to first element in the array.
odom.position_variance[0] = vpe.covariance[0]; // X row 0, col 0
odom.position_variance[1] = vpe.covariance[6]; // Y row 1, col 1
odom.position_variance[2] = vpe.covariance[11]; // Z row 2, col 2
sensor_optical_flow.timestamp_sample = hrt_absolute_time();
sensor_optical_flow.device_id = device_id.devid;
odom.orientation_variance[0] = vpe.covariance[15]; // R row 3, col 3
odom.orientation_variance[1] = vpe.covariance[18]; // P row 4, col 4
odom.orientation_variance[2] = vpe.covariance[20]; // Y row 5, col 5
sensor_optical_flow.pixel_flow[0] = flow.integrated_x;
sensor_optical_flow.pixel_flow[1] = flow.integrated_y;
odom.reset_counter = vpe.reset_counter;
sensor_optical_flow.integration_timespan_us = flow.integration_time_us;
sensor_optical_flow.quality = flow.quality;
odom.timestamp = hrt_absolute_time();
int index = (int) position_source::FLOW;
if (position_source_data[index].fail) {
uint32_t duration = position_source_data[index].failure_duration;
hrt_abstime start = position_source_data[index].failure_duration_start;
if (duration) {
if (hrt_elapsed_time(&start) > (duration * 1000000)) {
PX4_INFO("Optical flow failure ending");
position_source_data[index].fail = false;
position_source_data[index].failure_duration = 0;
position_source_data[index].failure_duration_start = 0;
} else {
sensor_optical_flow.quality = 0;
}
} else {
sensor_optical_flow.quality = 0;
}
}
const matrix::Vector3f integrated_gyro(flow.integrated_xgyro, flow.integrated_ygyro, flow.integrated_zgyro);
if (integrated_gyro.isAllFinite()) {
integrated_gyro.copyTo(sensor_optical_flow.delta_angle);
sensor_optical_flow.delta_angle_available = true;
}
sensor_optical_flow.max_flow_rate = NAN;
sensor_optical_flow.min_ground_distance = NAN;
sensor_optical_flow.max_ground_distance = NAN;
// Use distance value for distance sensor topic
// if (PX4_ISFINITE(flow.distance) && (flow.distance >= 0.f)) {
// // Positive value (including zero): distance known. Negative value: Unknown distance.
// sensor_optical_flow.distance_m = flow.distance;
// sensor_optical_flow.distance_available = true;
// }
// Emulate voxl-flow-server where distance comes in a separate
// distance sensor topic message
sensor_optical_flow.distance_m = 0.0f;
sensor_optical_flow.distance_available = false;
sensor_optical_flow.timestamp = hrt_absolute_time();
_sensor_optical_flow_pub.publish(sensor_optical_flow);
flow_sent_counter++;
}
int distance_debug_counter = 0;
void handle_message_distance_sensor(mavlink_message_t *msg)
{
mavlink_distance_sensor_t dist_sensor;
mavlink_msg_distance_sensor_decode(msg, &dist_sensor);
if ((_debug) && (!(distance_debug_counter % 10))) {
PX4_INFO("distance: time: %u, quality: %u, height: %u",
dist_sensor.time_boot_ms, dist_sensor.signal_quality,
dist_sensor.current_distance);
}
distance_debug_counter++;
distance_sensor_s ds{};
device::Device::DeviceId device_id;
device_id.devid_s.bus_type = device::Device::DeviceBusType::DeviceBusType_MAVLINK;
device_id.devid_s.bus = 1;
device_id.devid_s.address = msg->sysid;
device_id.devid_s.devtype = DRV_DIST_DEVTYPE_MAVLINK;
ds.timestamp = hrt_absolute_time(); /* Use system time for now, don't trust sender to attach correct timestamp */
ds.min_distance = static_cast<float>(dist_sensor.min_distance) * 1e-2f; /* cm to m */
ds.max_distance = static_cast<float>(dist_sensor.max_distance) * 1e-2f; /* cm to m */
ds.current_distance = static_cast<float>(dist_sensor.current_distance) * 1e-2f; /* cm to m */
ds.variance = dist_sensor.covariance * 1e-4f; /* cm^2 to m^2 */
ds.h_fov = dist_sensor.horizontal_fov;
ds.v_fov = dist_sensor.vertical_fov;
ds.q[0] = dist_sensor.quaternion[0];
ds.q[1] = dist_sensor.quaternion[1];
ds.q[2] = dist_sensor.quaternion[2];
ds.q[3] = dist_sensor.quaternion[3];
ds.type = dist_sensor.type;
ds.device_id = device_id.devid;
ds.orientation = dist_sensor.orientation;
// MAVLink DISTANCE_SENSOR signal_quality value of 0 means unset/unknown
// quality value. Also it comes normalised between 1 and 100 while the uORB
// signal quality is normalised between 0 and 100.
ds.signal_quality = dist_sensor.signal_quality == 0 ? -1 : 100 * (dist_sensor.signal_quality - 1) / 99;
_distance_sensor_pub.publish(ds);
distance_sent_counter++;
_visual_odometry_pub.publish(odom);
vision_msg_counter++;
}
void
@@ -666,8 +518,6 @@ handle_message_odometry_dsp(mavlink_message_t *msg)
mavlink_odometry_t odom_in;
mavlink_msg_odometry_decode(msg, &odom_in);
odometry_sent_counter++;
// fill vehicle_odometry from Mavlink ODOMETRY
vehicle_odometry_s odom{};
uint64_t timestamp = hrt_absolute_time();
@@ -849,28 +699,6 @@ handle_message_odometry_dsp(mavlink_message_t *msg)
odom.reset_counter = odom_in.reset_counter;
odom.quality = odom_in.quality;
int index = (int) position_source::VIO;
if (position_source_data[index].fail) {
uint32_t duration = position_source_data[index].failure_duration;
hrt_abstime start = position_source_data[index].failure_duration_start;
if (duration) {
if (hrt_elapsed_time(&start) > (duration * 1000000)) {
PX4_INFO("VIO failure ending");
position_source_data[index].fail = false;
position_source_data[index].failure_duration = 0;
position_source_data[index].failure_duration_start = 0;
} else {
odom.quality = 0;
}
} else {
odom.quality = 0;
}
}
switch (odom_in.estimator_type) {
case MAV_ESTIMATOR_TYPE_UNKNOWN: // accept MAV_ESTIMATOR_TYPE_UNKNOWN for legacy support
case MAV_ESTIMATOR_TYPE_NAIVE:
@@ -917,6 +745,10 @@ void actuator_controls_from_outputs_dsp(mavlink_hil_actuator_controls_t *msg)
msg->mode = mode_flag_custom;
msg->mode |= (armed) ? mode_flag_armed : 0;
msg->flags = 0;
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
msg->flags |= 1;
#endif
}
int openPort(const char *dev, speed_t speed)
@@ -927,8 +759,7 @@ int openPort(const char *dev, speed_t speed)
}
_uart_fd = qurt_uart_open(dev, speed);
if (_debug) { PX4_INFO("qurt_uart_opened"); }
PX4_DEBUG("qurt_uart_opened");
if (_uart_fd < 0) {
PX4_ERR("Error opening port: %s (%i)", dev, errno);
@@ -1009,50 +840,25 @@ int stop()
void usage()
{
PX4_INFO("Usage: dsp_hitl {start|status|clear|failure|stop}");
PX4_INFO(" failure <source> <duration>");
PX4_INFO(" source: gps, vio, flow");
PX4_INFO(" duration: 0 (toggle state), else seconds");
PX4_INFO("Usage: dsp_hitl {start|info|status|stop}");
}
void print_status()
int get_status()
{
PX4_INFO("Running: %s", _is_running ? "yes" : "no");
PX4_INFO("HIL Sensor received: %i", hil_sensor_counter);
PX4_INFO("IMU updates: %i", imu_counter);
PX4_INFO("\tCurrent accel x, y, z: %f, %f, %f", double(x_accel), double(y_accel), double(z_accel));
PX4_INFO("\tCurrent gyro x, y, z: %f, %f, %f", double(x_gyro), double(y_gyro), double(z_gyro));
PX4_INFO("Magnetometer sent: %i", mag_counter);
PX4_INFO("Barometer sent: %i", baro_counter);
PX4_INFO("Heartbeat received: %i, sent: %i", heartbeat_received_counter, heartbeat_sent_counter);
PX4_INFO("Odometry received: %i, sent: %i", odometry_received_counter, odometry_sent_counter);
PX4_INFO("GPS received: %i, sent: %i", gps_received_counter, gps_sent_counter);
PX4_INFO("Distance sensor received: %i, sent: %i", distance_received_counter, distance_sent_counter);
PX4_INFO("Optical flow received: %i, sent: %i", flow_received_counter, flow_sent_counter);
PX4_INFO("Actuator updates sent: %i", actuator_sent_counter);
PX4_INFO("Unknown messages received: %i", unknown_msg_received_counter);
PX4_INFO("Status of IMU_Data counter: %i", imu_counter);
PX4_INFO("Value of current accel x, y, z data: %f, %f, %f", double(x_accel), double(y_accel), double(z_accel));
PX4_INFO("Value of current gyro x, y, z data: %f, %f, %f", double(x_gyro), double(y_gyro), double(z_gyro));
PX4_INFO("Value of HIL_Sensor counter: %i", hil_sensor_counter);
PX4_INFO("Value of Heartbeat counter: %i", heartbeat_counter);
PX4_INFO("Value of Vision data counter: %i", vision_msg_counter);
PX4_INFO("Value of GPS Data counter: %i", gps_counter);
return 0;
}
void
clear_status_counters()
{
heartbeat_received_counter = 0;
heartbeat_sent_counter = 0;
imu_counter = 0;
hil_sensor_counter = 0;
mag_counter = 0;
baro_counter = 0;
actuator_sent_counter = 0;
odometry_received_counter = 0;
odometry_sent_counter = 0;
gps_received_counter = 0;
gps_sent_counter = 0;
distance_received_counter = 0;
distance_sent_counter = 0;
flow_received_counter = 0;
flow_sent_counter = 0;
unknown_msg_received_counter = 0;
}
uint64_t first_sensor_msg_timestamp = 0;
uint64_t first_sensor_report_timestamp = 0;
uint64_t last_sensor_report_timestamp = 0;
void
handle_message_hil_sensor_dsp(mavlink_message_t *msg)
@@ -1122,8 +928,6 @@ handle_message_hil_sensor_dsp(mavlink_message_t *msg)
}
_px4_mag->update(gyro_accel_time, hil_sensor.xmag, hil_sensor.ymag, hil_sensor.zmag);
mag_counter++;
}
}
@@ -1138,8 +942,17 @@ handle_message_hil_sensor_dsp(mavlink_message_t *msg)
sensor_baro.error_count = 0;
sensor_baro.timestamp = hrt_absolute_time();
_sensor_baro_pub.publish(sensor_baro);
}
baro_counter++;
// differential pressure
if ((hil_sensor.fields_updated & SensorSource::DIFF_PRESS) == SensorSource::DIFF_PRESS) {
differential_pressure_s report{};
report.timestamp_sample = gyro_accel_time;
report.device_id = 1377548; // 1377548: DRV_DIFF_PRESS_DEVTYPE_SIM, BUS: 1, ADDR: 5, TYPE: SIMULATION
report.temperature = hil_sensor.temperature;
report.differential_pressure_pa = hil_sensor.diff_pressure * 100.0f; // hPa to Pa
report.timestamp = hrt_absolute_time();
_differential_pressure_pub.publish(report);
}
// battery status
@@ -1157,6 +970,7 @@ handle_message_hil_sensor_dsp(mavlink_message_t *msg)
_battery_pub.publish(hil_battery_status);
}
hil_sensor_counter++;
}
void
@@ -1175,41 +989,15 @@ handle_message_hil_gps_dsp(mavlink_message_t *msg)
gps.device_id = device_id.devid;
gps.latitude_deg = hil_gps.lat * 1e-7;
gps.longitude_deg = hil_gps.lon * 1e-7;
gps.altitude_msl_m = hil_gps.alt * 1e-3;
gps.altitude_ellipsoid_m = hil_gps.alt * 1e-3;
gps.lat = hil_gps.lat;
gps.lon = hil_gps.lon;
gps.alt = hil_gps.alt;
gps.alt_ellipsoid = hil_gps.alt;
gps.s_variance_m_s = 0.25f;
gps.c_variance_rad = 0.5f;
gps.satellites_used = hil_gps.satellites_visible;
gps.fix_type = hil_gps.fix_type;
int index = (int) position_source::GPS;
if (position_source_data[index].fail) {
uint32_t duration = position_source_data[index].failure_duration;
hrt_abstime start = position_source_data[index].failure_duration_start;
if (duration) {
if (hrt_elapsed_time(&start) > (duration * 1000000)) {
PX4_INFO("GPS failure ending");
position_source_data[index].fail = false;
position_source_data[index].failure_duration = 0;
position_source_data[index].failure_duration_start = 0;
} else {
gps.satellites_used = 1;
gps.fix_type = 0;
}
} else {
gps.satellites_used = 1;
gps.fix_type = 0;
}
}
gps.eph = (float)hil_gps.eph * 1e-2f; // cm -> m
gps.epv = (float)hil_gps.epv * 1e-2f; // cm -> m
@@ -1233,6 +1021,7 @@ handle_message_hil_gps_dsp(mavlink_message_t *msg)
gps.timestamp_time_relative = 0;
gps.time_utc_usec = hil_gps.time_usec;
gps.satellites_used = hil_gps.satellites_visible;
gps.heading = NAN;
gps.heading_offset = NAN;
@@ -1240,51 +1029,10 @@ handle_message_hil_gps_dsp(mavlink_message_t *msg)
gps.timestamp = hrt_absolute_time();
_sensor_gps_pub.publish(gps);
gps_sent_counter++;
gps_counter++;
}
int
process_failure(dsp_hitl::position_source src, int duration)
{
if (src >= position_source::NUM_POSITION_SOURCES) {
return 1;
}
int index = (int) src;
if (position_source_data[index].send) {
if (duration <= 0) {
// Toggle state
if (position_source_data[index].fail) {
PX4_INFO("Ending indefinite %s failure", position_source_data[index].label);
position_source_data[index].fail = false;
} else {
PX4_INFO("Starting indefinite %s failure", position_source_data[index].label);
position_source_data[index].fail = true;
}
position_source_data[index].failure_duration = 0;
position_source_data[index].failure_duration_start = 0;
} else {
PX4_INFO("%s failure for %d seconds", position_source_data[index].label, duration);
position_source_data[index].fail = true;
position_source_data[index].failure_duration = duration;
position_source_data[index].failure_duration_start = hrt_absolute_time();
}
} else {
PX4_ERR("%s not active, cannot create failure", position_source_data[index].label);
return 1;
}
return 0;
}
} // End dsp_hitl namespace
int dsp_hitl_main(int argc, char *argv[])
{
int myoptind = 1;
@@ -1296,47 +1044,20 @@ int dsp_hitl_main(int argc, char *argv[])
const char *verb = argv[myoptind];
if (!strcmp(verb, "start")) {
return dsp_hitl::start(argc - 1, argv + 1);
}
} else if (!strcmp(verb, "stop")) {
else if (!strcmp(verb, "stop")) {
return dsp_hitl::stop();
}
} else if (!strcmp(verb, "status")) {
dsp_hitl::print_status();
return 0;
else if (!strcmp(verb, "status")) {
return dsp_hitl::get_status();
}
} else if (!strcmp(verb, "clear")) {
dsp_hitl::clear_status_counters();
return 0;
} else if (!strcmp(verb, "failure")) {
if (argc != 4) {
dsp_hitl::usage();
return 1;
}
const char *source = argv[myoptind + 1];
int duration = atoi(argv[myoptind + 2]);
if (!strcmp(source, "gps")) {
return dsp_hitl::process_failure(dsp_hitl::position_source::GPS, duration);
} else if (!strcmp(source, "vio")) {
return dsp_hitl::process_failure(dsp_hitl::position_source::VIO, duration);
} else if (!strcmp(source, "flow")) {
return dsp_hitl::process_failure(dsp_hitl::position_source::FLOW, duration);
} else {
PX4_ERR("Unknown failure source %s, duration %d", source, duration);
dsp_hitl::usage();
return 1;
}
return 0;
} else {
else {
dsp_hitl::usage();
return 1;
}
@@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2024 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
@@ -31,14 +31,18 @@
#
############################################################################
px4_add_module(
MODULE drivers__magnetometer__memsic__mmc5983ma
MAIN mmc5983ma
MODULE drivers__imu__invensense__icm42688p
MAIN icm42688p
COMPILE_FLAGS
${MAX_CUSTOM_OPT_LEVEL}
SRCS
mmc5983ma_i2c.cpp
mmc5983ma_main.cpp
mmc5983ma.cpp
icm42688p_main.cpp
ICM42688P.cpp
ICM42688P.hpp
InvenSense_ICM42688P_registers.hpp
DEPENDS
drivers_magnetometer
px4_work_queue
drivers_accelerometer
drivers_gyroscope
drivers__device
)
@@ -0,0 +1,991 @@
/****************************************************************************
*
* 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "ICM42688P.hpp"
bool hitl_mode = false;
using namespace time_literals;
static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
{
return (msb << 8u) | lsb;
}
ICM42688P::ICM42688P(const I2CSPIDriverConfig &config) :
// SPI(DRV_IMU_DEVTYPE_ICM42688P, MODULE_NAME, bus, device, spi_mode, bus_frequency),
// I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
// _drdy_gpio(drdy_gpio)
SPI(config),
I2CSPIDriver(config),
_drdy_gpio(config.drdy_gpio),
_px4_accel(get_device_id(), config.rotation),
_px4_gyro(get_device_id(), config.rotation)
{
if (config.drdy_gpio != 0) {
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
}
if (!hitl_mode) {
// _px4_accel = std::make_shared<PX4Accelerometer>(get_device_id(), rotation);
// _px4_gyro = std::make_shared<PX4Gyroscope>(get_device_id(), rotation);
ConfigureSampleRate(_px4_gyro.get_max_rate_hz());
// _imu_server_pub.advertise();
} else {
ConfigureSampleRate(0);
}
}
ICM42688P::~ICM42688P()
{
perf_free(_bad_register_perf);
perf_free(_bad_transfer_perf);
perf_free(_fifo_empty_perf);
perf_free(_fifo_overflow_perf);
perf_free(_fifo_reset_perf);
perf_free(_drdy_missed_perf);
// if (!hitl_mode){
// _imu_server_pub.unadvertise();
// }
}
int ICM42688P::init()
{
int ret = SPI::init();
if (ret != PX4_OK) {
DEVICE_DEBUG("SPI::init failed (%i)", ret);
return ret;
}
return Reset() ? 0 : -1;
}
bool ICM42688P::Reset()
{
_state = STATE::RESET;
DataReadyInterruptDisable();
ScheduleClear();
ScheduleNow();
return true;
}
void ICM42688P::exit_and_cleanup()
{
DataReadyInterruptDisable();
I2CSPIDriverBase::exit_and_cleanup();
}
void ICM42688P::print_status()
{
I2CSPIDriverBase::print_status();
PX4_INFO("FIFO empty interval: %d us (%.1f Hz)", _fifo_empty_interval_us, 1e6 / _fifo_empty_interval_us);
perf_print_counter(_bad_register_perf);
perf_print_counter(_bad_transfer_perf);
perf_print_counter(_fifo_empty_perf);
perf_print_counter(_fifo_overflow_perf);
perf_print_counter(_fifo_reset_perf);
perf_print_counter(_drdy_missed_perf);
}
int ICM42688P::probe()
{
for (int i = 0; i < 3; i++) {
uint8_t whoami = RegisterRead(Register::BANK_0::WHO_AM_I);
if (whoami == WHOAMI) {
PX4_INFO("ICM42688P::probe successful!");
return PX4_OK;
} else {
DEVICE_DEBUG("unexpected WHO_AM_I 0x%02x", whoami);
uint8_t reg_bank_sel = RegisterRead(Register::BANK_0::REG_BANK_SEL);
int bank = reg_bank_sel >> 4;
if (bank >= 1 && bank <= 3) {
DEVICE_DEBUG("incorrect register bank for WHO_AM_I REG_BANK_SEL:0x%02x, bank:%d", reg_bank_sel, bank);
// force bank selection and retry
SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0, true);
}
}
}
return PX4_ERROR;
}
void ICM42688P::RunImpl()
{
PX4_INFO(">>> ICM42688P this: %p", this);
const hrt_abstime now = hrt_absolute_time();
switch (_state) {
case STATE::RESET:
// DEVICE_CONFIG: Software reset configuration
RegisterWrite(Register::BANK_0::DEVICE_CONFIG, DEVICE_CONFIG_BIT::SOFT_RESET_CONFIG);
_reset_timestamp = now;
_failure_count = 0;
_state = STATE::WAIT_FOR_RESET;
ScheduleDelayed(2_ms); // to be safe wait 2 ms for soft reset to be effective
break;
case STATE::WAIT_FOR_RESET:
if ((RegisterRead(Register::BANK_0::WHO_AM_I) == WHOAMI)
&& (RegisterRead(Register::BANK_0::DEVICE_CONFIG) == 0x00)
&& (RegisterRead(Register::BANK_0::INT_STATUS) & INT_STATUS_BIT::RESET_DONE_INT)) {
_state = STATE::CONFIGURE;
ScheduleDelayed(10_ms); // 30 ms gyro startup time, 10 ms accel from sleep to valid data
} else {
// RESET not complete
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
PX4_DEBUG("Reset failed, retrying");
_state = STATE::RESET;
ScheduleDelayed(100_ms);
} else {
PX4_DEBUG("Reset not complete, check again in 10 ms");
ScheduleDelayed(10_ms);
}
}
break;
case STATE::CONFIGURE:
if (Configure()) {
// Wakeup accel and gyro after configuring registers
ScheduleDelayed(1_ms); // add a delay here to be safe
RegisterWrite(Register::BANK_0::PWR_MGMT0, PWR_MGMT0_BIT::GYRO_MODE_LOW_NOISE | PWR_MGMT0_BIT::ACCEL_MODE_LOW_NOISE);
ScheduleDelayed(30_ms); // 30 ms gyro startup time, 10 ms accel from sleep to valid data
// if configure succeeded then start reading from FIFO
_state = STATE::FIFO_READ;
if (DataReadyInterruptConfigure()) {
_data_ready_interrupt_enabled = true;
// backup schedule as a watchdog timeout
ScheduleDelayed(100_ms);
} else {
PX4_ERR("ICM42688P::RunImpl interrupt configuration failed");
_data_ready_interrupt_enabled = false;
ScheduleOnInterval(_fifo_empty_interval_us, _fifo_empty_interval_us);
}
FIFOReset();
} else {
PX4_ERR("ICM42688P::RunImpl configuration failed");
// CONFIGURE not complete
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
PX4_DEBUG("Configure failed, resetting");
_state = STATE::RESET;
} else {
PX4_DEBUG("Configure failed, retrying");
}
ScheduleDelayed(100_ms);
}
break;
case STATE::FIFO_READ: {
#ifndef __PX4_QURT
uint32_t samples = 0;
if (_data_ready_interrupt_enabled) {
// scheduled from interrupt if _drdy_fifo_read_samples was set as expected
if (_drdy_fifo_read_samples.fetch_and(0) != _fifo_gyro_samples) {
perf_count(_drdy_missed_perf);
} else {
samples = _fifo_gyro_samples;
}
// push backup schedule back
ScheduleDelayed(_fifo_empty_interval_us * 2);
}
if (samples == 0) {
// check current FIFO count
const uint16_t fifo_count = FIFOReadCount();
if (fifo_count >= FIFO::SIZE) {
FIFOReset();
perf_count(_fifo_overflow_perf);
} else if (fifo_count == 0) {
perf_count(_fifo_empty_perf);
} else {
// FIFO count (size in bytes)
samples = (fifo_count / sizeof(FIFO::DATA));
if (samples > FIFO_MAX_SAMPLES) {
// not technically an overflow, but more samples than we expected or can publish
FIFOReset();
perf_count(_fifo_overflow_perf);
samples = 0;
}
}
}
bool success = false;
if (samples >= 1) {
if (FIFORead(now, samples)) {
success = true;
if (_failure_count > 0) {
_failure_count--;
}
}
}
if (!success) {
_failure_count++;
// full reset if things are failing consistently
if (_failure_count > 10) {
Reset();
return;
}
}
// check configuration registers periodically or immediately following any failure
if (RegisterCheck(_register_bank0_cfg[_checked_register_bank0])
&& RegisterCheck(_register_bank1_cfg[_checked_register_bank1])
&& RegisterCheck(_register_bank2_cfg[_checked_register_bank2])
) {
_last_config_check_timestamp = now;
_checked_register_bank0 = (_checked_register_bank0 + 1) % size_register_bank0_cfg;
_checked_register_bank1 = (_checked_register_bank1 + 1) % size_register_bank1_cfg;
_checked_register_bank2 = (_checked_register_bank2 + 1) % size_register_bank2_cfg;
} else {
// register check failed, force reset
perf_count(_bad_register_perf);
Reset();
}
#endif
}
break;
}
}
void ICM42688P::ConfigureSampleRate(int sample_rate)
{
if (sample_rate == 0) {
sample_rate = 800; // default to 800 Hz
}
// round down to nearest FIFO sample dt
const float min_interval = FIFO_SAMPLE_DT;
_fifo_empty_interval_us = math::max(roundf((1e6f / (float)sample_rate) / min_interval) * min_interval, min_interval);
_fifo_gyro_samples = roundf(math::min((float)_fifo_empty_interval_us / (1e6f / GYRO_RATE), (float)FIFO_MAX_SAMPLES));
// recompute FIFO empty interval (us) with actual gyro sample limit
_fifo_empty_interval_us = _fifo_gyro_samples * (1e6f / GYRO_RATE);
ConfigureFIFOWatermark(_fifo_gyro_samples);
}
void ICM42688P::ConfigureFIFOWatermark(uint8_t samples)
{
// FIFO watermark threshold in number of bytes
const uint16_t fifo_watermark_threshold = samples * sizeof(FIFO::DATA);
for (auto &r : _register_bank0_cfg) {
if (r.reg == Register::BANK_0::FIFO_CONFIG2) {
// FIFO_WM[7:0] FIFO_CONFIG2
r.set_bits = fifo_watermark_threshold & 0xFF;
} else if (r.reg == Register::BANK_0::FIFO_CONFIG3) {
// FIFO_WM[11:8] FIFO_CONFIG3
r.set_bits = (fifo_watermark_threshold >> 8) & 0x0F;
}
}
}
void ICM42688P::SelectRegisterBank(enum REG_BANK_SEL_BIT bank, bool force)
{
if (bank != _last_register_bank || force) {
// select BANK_0
uint8_t cmd_bank_sel[2] {};
cmd_bank_sel[0] = static_cast<uint8_t>(Register::BANK_0::REG_BANK_SEL);
cmd_bank_sel[1] = bank;
transfer(cmd_bank_sel, cmd_bank_sel, sizeof(cmd_bank_sel));
_last_register_bank = bank;
}
}
bool ICM42688P::Configure()
{
// first set and clear all configured register bits
for (const auto &reg_cfg : _register_bank0_cfg) {
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
}
for (const auto &reg_cfg : _register_bank1_cfg) {
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
}
for (const auto &reg_cfg : _register_bank2_cfg) {
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
}
// now check that all are configured
bool success = true;
for (const auto &reg_cfg : _register_bank0_cfg) {
if (!RegisterCheck(reg_cfg)) {
success = false;
}
}
for (const auto &reg_cfg : _register_bank1_cfg) {
if (!RegisterCheck(reg_cfg)) {
success = false;
}
}
for (const auto &reg_cfg : _register_bank2_cfg) {
if (!RegisterCheck(reg_cfg)) {
success = false;
}
}
// // 20-bits data format used
// // the only FSR settings that are operational are ±2000dps for gyroscope and ±16g for accelerometer
if (!hitl_mode) {
_px4_accel.set_range(16.f * CONSTANTS_ONE_G);
_px4_accel.set_scale(CONSTANTS_ONE_G / 8192.f);
_px4_gyro.set_range(math::radians(2000.f));
_px4_gyro.set_scale(math::radians(1.f / 131.f));
}
return success;
}
static bool interrupt_debug = false;
static uint32_t interrupt_debug_count = 0;
static const uint32_t interrupt_debug_trigger = 800;
static hrt_abstime last_interrupt_time = 0;
static hrt_abstime avg_interrupt_delta = 0;
static hrt_abstime max_interrupt_delta = 0;
static hrt_abstime min_interrupt_delta = 60 * 1000 * 1000;
static hrt_abstime cumulative_interrupt_delta = 0;
int ICM42688P::DataReadyInterruptCallback(int irq, void *context, void *arg)
{
hrt_abstime current_interrupt_time = hrt_absolute_time();
if (interrupt_debug) {
if (last_interrupt_time) {
hrt_abstime interrupt_delta_time = current_interrupt_time - last_interrupt_time;
if (interrupt_delta_time > max_interrupt_delta) { max_interrupt_delta = interrupt_delta_time; }
if (interrupt_delta_time < min_interrupt_delta) { min_interrupt_delta = interrupt_delta_time; }
cumulative_interrupt_delta += interrupt_delta_time;
}
last_interrupt_time = current_interrupt_time;
interrupt_debug_count++;
if (interrupt_debug_count == interrupt_debug_trigger) {
avg_interrupt_delta = cumulative_interrupt_delta / interrupt_debug_trigger;
PX4_INFO(">>> Max: %llu, Min: %llu, Avg: %llu", max_interrupt_delta,
min_interrupt_delta, avg_interrupt_delta);
interrupt_debug_count = 0;
cumulative_interrupt_delta = 0;
}
}
static_cast<ICM42688P *>(arg)->DataReady();
return 0;
}
void ICM42688P::DataReady()
{
#ifndef __PX4_QURT
uint32_t expected = 0;
if (_drdy_fifo_read_samples.compare_exchange(&expected, _fifo_gyro_samples)) {
ScheduleNow();
}
#else
uint16_t fifo_byte_count = FIFOReadCount();
FIFORead(hrt_absolute_time(), fifo_byte_count / sizeof(FIFO::DATA));
#endif
}
bool ICM42688P::DataReadyInterruptConfigure()
{
if (_drdy_gpio == 0) {
return false;
}
// Setup data ready on falling edge
return px4_arch_gpiosetevent(_drdy_gpio, false, true, true, &DataReadyInterruptCallback, this) == 0;
}
bool ICM42688P::DataReadyInterruptDisable()
{
if (_drdy_gpio == 0) {
return false;
}
return px4_arch_gpiosetevent(_drdy_gpio, false, false, false, nullptr, nullptr) == 0;
}
template <typename T>
bool ICM42688P::RegisterCheck(const T &reg_cfg)
{
bool success = true;
const uint8_t reg_value = RegisterRead(reg_cfg.reg);
if (reg_cfg.set_bits && ((reg_value & reg_cfg.set_bits) != reg_cfg.set_bits)) {
PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not set)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.set_bits);
success = false;
}
if (reg_cfg.clear_bits && ((reg_value & reg_cfg.clear_bits) != 0)) {
PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not cleared)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.clear_bits);
success = false;
}
return success;
}
template <typename T>
uint8_t ICM42688P::RegisterRead(T reg)
{
uint8_t cmd[2] {};
cmd[0] = static_cast<uint8_t>(reg) | DIR_READ;
SelectRegisterBank(reg);
transfer(cmd, cmd, sizeof(cmd));
return cmd[1];
}
template <typename T>
void ICM42688P::RegisterWrite(T reg, uint8_t value)
{
uint8_t cmd[2] { (uint8_t)reg, value };
SelectRegisterBank(reg);
transfer(cmd, cmd, sizeof(cmd));
}
template <typename T>
void ICM42688P::RegisterSetAndClearBits(T reg, uint8_t setbits, uint8_t clearbits)
{
const uint8_t orig_val = RegisterRead(reg);
uint8_t val = (orig_val & ~clearbits) | setbits;
if (orig_val != val) {
RegisterWrite(reg, val);
}
}
uint16_t ICM42688P::FIFOReadCount()
{
// read FIFO count
uint8_t fifo_count_buf[3] {};
fifo_count_buf[0] = static_cast<uint8_t>(Register::BANK_0::FIFO_COUNTH) | DIR_READ;
SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0);
if (transfer(fifo_count_buf, fifo_count_buf, sizeof(fifo_count_buf)) != PX4_OK) {
perf_count(_bad_transfer_perf);
return 0;
}
return combine(fifo_count_buf[1], fifo_count_buf[2]);
}
// static uint32_t debug_decimator = 0;
// static hrt_abstime last_sample_time = 0;
// static bool imu_debug = true;
bool ICM42688P::FIFORead(const hrt_abstime &timestamp_sample, uint16_t samples)
{
FIFOTransferBuffer buffer{};
const size_t max_transfer_size = 10 * sizeof(FIFO::DATA) + 4;
const size_t transfer_size = math::min(samples * sizeof(FIFO::DATA) + 4, max_transfer_size);
SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0);
if (transfer((uint8_t *)&buffer, (uint8_t *)&buffer, transfer_size) != PX4_OK) {
perf_count(_bad_transfer_perf);
return false;
}
if (buffer.INT_STATUS & INT_STATUS_BIT::FIFO_FULL_INT) {
perf_count(_fifo_overflow_perf);
FIFOReset();
return false;
}
const uint16_t fifo_count_bytes = combine(buffer.FIFO_COUNTH, buffer.FIFO_COUNTL);
if (fifo_count_bytes >= FIFO::SIZE) {
perf_count(_fifo_overflow_perf);
FIFOReset();
return false;
}
const uint16_t fifo_count_samples = fifo_count_bytes / sizeof(FIFO::DATA);
if (fifo_count_samples == 0) {
perf_count(_fifo_empty_perf);
return false;
}
// check FIFO header in every sample
uint16_t valid_samples = 0;
// for (int i = 0; i < math::min(samples, fifo_count_samples); i++) {
for (int i = 0; i < math::min(samples, (uint16_t) 10); i++) {
bool valid = true;
// With FIFO_ACCEL_EN and FIFO_GYRO_EN header should be 8b_0110_10xx
const uint8_t FIFO_HEADER = buffer.f[i].FIFO_Header;
if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_MSG) {
// FIFO sample empty if HEADER_MSG set
valid = false;
} else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ACCEL)) {
// accel bit not set
valid = false;
} else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_GYRO)) {
// gyro bit not set
valid = false;
} else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_20)) {
// Packet does not contain a new and valid extended 20-bit data
valid = false;
} else if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ODR_ACCEL) {
// accel ODR changed
valid = false;
} else if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ODR_GYRO) {
// gyro ODR changed
valid = false;
}
if (valid) {
valid_samples++;
} else {
perf_count(_bad_transfer_perf);
break;
}
}
// if (imu_debug) {
// debug_decimator++;
// if (debug_decimator == 801) {
// debug_decimator = 0;
// PX4_INFO("Initial: %u Next: %u Valid: %u Delta: %llu", samples, fifo_count_samples, valid_samples, timestamp_sample - last_sample_time);
// }
// last_sample_time = timestamp_sample;
// }
if (valid_samples > 0) {
if (ProcessTemperature(buffer.f, valid_samples)) {
ProcessGyro(timestamp_sample, buffer.f, valid_samples);
ProcessAccel(timestamp_sample, buffer.f, valid_samples);
ProcessIMU(timestamp_sample, buffer.f, valid_samples);
return true;
}
}
return false;
}
void ICM42688P::FIFOReset()
{
perf_count(_fifo_reset_perf);
// SIGNAL_PATH_RESET: FIFO flush
RegisterSetBits(Register::BANK_0::SIGNAL_PATH_RESET, SIGNAL_PATH_RESET_BIT::FIFO_FLUSH);
// reset while FIFO is disabled
_drdy_fifo_read_samples.store(0);
}
static constexpr int32_t reassemble_20bit(const uint32_t a, const uint32_t b, const uint32_t c)
{
// 0xXXXAABBC
uint32_t high = ((a << 12) & 0x000FF000);
uint32_t low = ((b << 4) & 0x00000FF0);
uint32_t lowest = (c & 0x0000000F);
uint32_t x = high | low | lowest;
if (a & Bit7) {
// sign extend
x |= 0xFFF00000u;
}
return static_cast<int32_t>(x);
}
void ICM42688P::ProcessIMU(const hrt_abstime &timestamp_sample, const FIFO::DATA fifo[], const uint8_t samples)
{
float accel_x = 0.0, accel_y = 0.0, accel_z = 0.0;
float gyro_x = 0.0, gyro_y = 0.0, gyro_z = 0.0;
for (int i = 0; i < samples; i++) {
_imu_server_decimator++;
if (_imu_server_decimator == 8) {
_imu_server_decimator = 0;
// 20 bit hires mode
// Sign extension + Accel [19:12] + Accel [11:4] + Accel [3:2] (20 bit extension byte)
// Accel data is 18 bit
int32_t temp_accel_x = reassemble_20bit(fifo[i].ACCEL_DATA_X1, fifo[i].ACCEL_DATA_X0,
fifo[i].Ext_Accel_X_Gyro_X & 0xF0 >> 4);
int32_t temp_accel_y = reassemble_20bit(fifo[i].ACCEL_DATA_Y1, fifo[i].ACCEL_DATA_Y0,
fifo[i].Ext_Accel_Y_Gyro_Y & 0xF0 >> 4);
int32_t temp_accel_z = reassemble_20bit(fifo[i].ACCEL_DATA_Z1, fifo[i].ACCEL_DATA_Z0,
fifo[i].Ext_Accel_Z_Gyro_Z & 0xF0 >> 4);
// Gyro [19:12] + Gyro [11:4] + Gyro [3:0] (bottom 4 bits of 20 bit extension byte)
int32_t temp_gyro_x = reassemble_20bit(fifo[i].GYRO_DATA_X1, fifo[i].GYRO_DATA_X0,
fifo[i].Ext_Accel_X_Gyro_X & 0x0F);
int32_t temp_gyro_y = reassemble_20bit(fifo[i].GYRO_DATA_Y1, fifo[i].GYRO_DATA_Y0,
fifo[i].Ext_Accel_Y_Gyro_Y & 0x0F);
int32_t temp_gyro_z = reassemble_20bit(fifo[i].GYRO_DATA_Z1, fifo[i].GYRO_DATA_Z0,
fifo[i].Ext_Accel_Z_Gyro_Z & 0x0F);
// accel samples invalid if -524288
if (temp_accel_x != -524288 && temp_accel_y != -524288 && temp_accel_z != -524288) {
// shift accel by 2 (2 least significant bits are always 0)
accel_x = (float) temp_accel_x / 4.f;
accel_y = (float) temp_accel_y / 4.f;
accel_z = (float) temp_accel_z / 4.f;
// shift gyro by 1 (least significant bit is always 0)
gyro_x = (float) temp_gyro_x / 2.f;
gyro_y = (float) temp_gyro_y / 2.f;
gyro_z = (float) temp_gyro_z / 2.f;
// correct frame for publication
// sensor's frame is +x forward, +y left, +z up
// flip y & z to publish right handed with z down (x forward, y right, z down)
accel_y = -accel_y;
accel_z = -accel_z;
gyro_y = -gyro_y;
gyro_z = -gyro_z;
// Scale everything appropriately
float accel_scale_factor = (CONSTANTS_ONE_G / 8192.f);
accel_x *= accel_scale_factor;
accel_y *= accel_scale_factor;
accel_z *= accel_scale_factor;
float gyro_scale_factor = math::radians(1.f / 131.f);
gyro_x *= gyro_scale_factor;
gyro_y *= gyro_scale_factor;
gyro_z *= gyro_scale_factor;
// Store the data in our array
_imu_server_data.accel_x[_imu_server_index] = accel_x;
_imu_server_data.accel_y[_imu_server_index] = accel_y;
_imu_server_data.accel_z[_imu_server_index] = accel_z;
_imu_server_data.gyro_x[_imu_server_index] = gyro_x;
_imu_server_data.gyro_y[_imu_server_index] = gyro_y;
_imu_server_data.gyro_z[_imu_server_index] = gyro_z;
_imu_server_data.ts[_imu_server_index] = timestamp_sample - (125 * (samples - 1 - i));
_imu_server_index++;
// If array is full, publish the data
if (_imu_server_index == 10) {
_imu_server_index = 0;
_imu_server_data.timestamp = hrt_absolute_time();
_imu_server_data.temperature = 0; // Not used right now
_imu_server_pub.publish(_imu_server_data);
}
}
}
}
}
void ICM42688P::ProcessAccel(const hrt_abstime &timestamp_sample, const FIFO::DATA fifo[], const uint8_t samples)
{
sensor_accel_fifo_s accel{};
accel.timestamp_sample = timestamp_sample;
accel.samples = 0;
accel.dt = FIFO_SAMPLE_DT;
// 18-bits of accelerometer data
bool scale_20bit = false;
// first pass
for (int i = 0; i < samples; i++) {
// 20 bit hires mode
// Sign extension + Accel [19:12] + Accel [11:4] + Accel [3:2] (20 bit extension byte)
// Accel data is 18 bit ()
int32_t accel_x = reassemble_20bit(fifo[i].ACCEL_DATA_X1, fifo[i].ACCEL_DATA_X0,
fifo[i].Ext_Accel_X_Gyro_X & 0xF0 >> 4);
int32_t accel_y = reassemble_20bit(fifo[i].ACCEL_DATA_Y1, fifo[i].ACCEL_DATA_Y0,
fifo[i].Ext_Accel_Y_Gyro_Y & 0xF0 >> 4);
int32_t accel_z = reassemble_20bit(fifo[i].ACCEL_DATA_Z1, fifo[i].ACCEL_DATA_Z0,
fifo[i].Ext_Accel_Z_Gyro_Z & 0xF0 >> 4);
// sample invalid if -524288
if (accel_x != -524288 && accel_y != -524288 && accel_z != -524288) {
// check if any values are going to exceed int16 limits
static constexpr int16_t max_accel = INT16_MAX;
static constexpr int16_t min_accel = INT16_MIN;
if (accel_x >= max_accel || accel_x <= min_accel) {
scale_20bit = true;
}
if (accel_y >= max_accel || accel_y <= min_accel) {
scale_20bit = true;
}
if (accel_z >= max_accel || accel_z <= min_accel) {
scale_20bit = true;
}
// shift by 2 (2 least significant bits are always 0)
accel.x[accel.samples] = accel_x / 4;
accel.y[accel.samples] = accel_y / 4;
accel.z[accel.samples] = accel_z / 4;
accel.samples++;
}
}
if (!scale_20bit) {
// if highres enabled accel data is always 8192 LSB/g
if (!hitl_mode) {
_px4_accel.set_scale(CONSTANTS_ONE_G / 8192.f);
}
} else {
// 20 bit data scaled to 16 bit (2^4)
for (int i = 0; i < samples; i++) {
// 20 bit hires mode
// Sign extension + Accel [19:12] + Accel [11:4] + Accel [3:2] (20 bit extension byte)
// Accel data is 18 bit ()
int16_t accel_x = combine(fifo[i].ACCEL_DATA_X1, fifo[i].ACCEL_DATA_X0);
int16_t accel_y = combine(fifo[i].ACCEL_DATA_Y1, fifo[i].ACCEL_DATA_Y0);
int16_t accel_z = combine(fifo[i].ACCEL_DATA_Z1, fifo[i].ACCEL_DATA_Z0);
accel.x[i] = accel_x;
accel.y[i] = accel_y;
accel.z[i] = accel_z;
}
if (!hitl_mode) {
_px4_accel.set_scale(CONSTANTS_ONE_G / 2048.f);
}
}
// correct frame for publication
for (int i = 0; i < accel.samples; i++) {
// sensor's frame is +x forward, +y left, +z up
// flip y & z to publish right handed with z down (x forward, y right, z down)
accel.x[i] = accel.x[i];
accel.y[i] = (accel.y[i] == INT16_MIN) ? INT16_MAX : -accel.y[i];
accel.z[i] = (accel.z[i] == INT16_MIN) ? INT16_MAX : -accel.z[i];
}
if (!hitl_mode) {
_px4_accel.set_error_count(perf_event_count(_bad_register_perf) + perf_event_count(_bad_transfer_perf) +
perf_event_count(_fifo_empty_perf) + perf_event_count(_fifo_overflow_perf));
}
if (accel.samples > 0) {
if (!hitl_mode) {
_px4_accel.updateFIFO(accel);
}
}
}
void ICM42688P::ProcessGyro(const hrt_abstime &timestamp_sample, const FIFO::DATA fifo[], const uint8_t samples)
{
sensor_gyro_fifo_s gyro{};
gyro.timestamp_sample = timestamp_sample;
gyro.samples = 0;
gyro.dt = FIFO_SAMPLE_DT;
// 20-bits of gyroscope data
bool scale_20bit = false;
// first pass
for (int i = 0; i < samples; i++) {
// 20 bit hires mode
// Gyro [19:12] + Gyro [11:4] + Gyro [3:0] (bottom 4 bits of 20 bit extension byte)
int32_t gyro_x = reassemble_20bit(fifo[i].GYRO_DATA_X1, fifo[i].GYRO_DATA_X0, fifo[i].Ext_Accel_X_Gyro_X & 0x0F);
int32_t gyro_y = reassemble_20bit(fifo[i].GYRO_DATA_Y1, fifo[i].GYRO_DATA_Y0, fifo[i].Ext_Accel_Y_Gyro_Y & 0x0F);
int32_t gyro_z = reassemble_20bit(fifo[i].GYRO_DATA_Z1, fifo[i].GYRO_DATA_Z0, fifo[i].Ext_Accel_Z_Gyro_Z & 0x0F);
// check if any values are going to exceed int16 limits
static constexpr int16_t max_gyro = INT16_MAX;
static constexpr int16_t min_gyro = INT16_MIN;
if (gyro_x >= max_gyro || gyro_x <= min_gyro) {
scale_20bit = true;
}
if (gyro_y >= max_gyro || gyro_y <= min_gyro) {
scale_20bit = true;
}
if (gyro_z >= max_gyro || gyro_z <= min_gyro) {
scale_20bit = true;
}
gyro.x[gyro.samples] = gyro_x / 2;
gyro.y[gyro.samples] = gyro_y / 2;
gyro.z[gyro.samples] = gyro_z / 2;
gyro.samples++;
}
if (!scale_20bit) {
// if highres enabled gyro data is always 131 LSB/dps
if (!hitl_mode) {
_px4_gyro.set_scale(math::radians(1.f / 131.f));
}
} else {
// 20 bit data scaled to 16 bit (2^4)
for (int i = 0; i < samples; i++) {
gyro.x[i] = combine(fifo[i].GYRO_DATA_X1, fifo[i].GYRO_DATA_X0);
gyro.y[i] = combine(fifo[i].GYRO_DATA_Y1, fifo[i].GYRO_DATA_Y0);
gyro.z[i] = combine(fifo[i].GYRO_DATA_Z1, fifo[i].GYRO_DATA_Z0);
}
if (!hitl_mode) {
_px4_gyro.set_scale(math::radians(2000.f / 32768.f));
}
}
// correct frame for publication
for (int i = 0; i < gyro.samples; i++) {
// sensor's frame is +x forward, +y left, +z up
// flip y & z to publish right handed with z down (x forward, y right, z down)
gyro.x[i] = gyro.x[i];
gyro.y[i] = (gyro.y[i] == INT16_MIN) ? INT16_MAX : -gyro.y[i];
gyro.z[i] = (gyro.z[i] == INT16_MIN) ? INT16_MAX : -gyro.z[i];
}
if (!hitl_mode) {
_px4_gyro.set_error_count(perf_event_count(_bad_register_perf) + perf_event_count(_bad_transfer_perf) +
perf_event_count(_fifo_empty_perf) + perf_event_count(_fifo_overflow_perf));
}
if (gyro.samples > 0) {
if (!hitl_mode) {
_px4_gyro.updateFIFO(gyro);
}
}
}
bool ICM42688P::ProcessTemperature(const FIFO::DATA fifo[], const uint8_t samples)
{
int16_t temperature[FIFO_MAX_SAMPLES];
float temperature_sum{0};
int valid_samples = 0;
for (int i = 0; i < samples; i++) {
const int16_t t = combine(fifo[i].TEMP_DATA1, fifo[i].TEMP_DATA0);
// sample invalid if -32768
if (t != -32768) {
temperature_sum += t;
temperature[valid_samples] = t;
valid_samples++;
}
}
if (valid_samples > 0) {
const float temperature_avg = temperature_sum / valid_samples;
for (int i = 0; i < valid_samples; i++) {
// temperature changing wildly is an indication of a transfer error
if (fabsf(temperature[i] - temperature_avg) > 1000) {
perf_count(_bad_transfer_perf);
return false;
}
}
// use average temperature reading
const float TEMP_degC = (temperature_avg / TEMPERATURE_SENSITIVITY) + TEMPERATURE_OFFSET;
if (PX4_ISFINITE(TEMP_degC)) {
if (!hitl_mode) {
_px4_accel.set_temperature(TEMP_degC);
_px4_gyro.set_temperature(TEMP_degC);
return true;
}
} else {
perf_count(_bad_transfer_perf);
}
}
return false;
}
@@ -0,0 +1,235 @@
/****************************************************************************
*
* 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ICM42688P.hpp
*
* Driver for the Invensense ICM42688P connected via SPI.
*
*/
#pragma once
#include "InvenSense_ICM42688P_registers.hpp"
#include <drivers/drv_hrt.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>
#include <uORB/topics/imu_server.h>
#include <uORB/topics/sensor_accel_fifo.h>
#include <uORB/topics/sensor_gyro_fifo.h>
#include <memory>
using namespace InvenSense_ICM42688P;
extern bool hitl_mode;
class ICM42688P : public device::SPI, public I2CSPIDriver<ICM42688P>
{
public:
// ICM42688P(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
// spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio);
ICM42688P(const I2CSPIDriverConfig &config);
~ICM42688P() override;
// static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
// int runtime_instance);
static void print_usage();
void RunImpl();
int init() override;
void print_status() override;
private:
void exit_and_cleanup() override;
// Sensor Configuration
static constexpr float IMU_ODR{8000.f}; // 8kHz accel & gyro ODR configured
static constexpr float FIFO_SAMPLE_DT{1e6f / IMU_ODR};
static constexpr float GYRO_RATE{1e6f / FIFO_SAMPLE_DT};
static constexpr float ACCEL_RATE{1e6f / FIFO_SAMPLE_DT};
// maximum FIFO samples per transfer is limited to the size of sensor_accel_fifo/sensor_gyro_fifo
// static constexpr uint32_t FIFO_MAX_SAMPLES{math::min(math::min(FIFO::SIZE / sizeof(FIFO::DATA), sizeof(sensor_gyro_fifo_s::x) / sizeof(sensor_gyro_fifo_s::x[0])), sizeof(sensor_accel_fifo_s::x) / sizeof(sensor_accel_fifo_s::x[0]) * (int)(GYRO_RATE / ACCEL_RATE))};
static constexpr uint32_t FIFO_MAX_SAMPLES{10};
// Transfer data
struct FIFOTransferBuffer {
uint8_t cmd{static_cast<uint8_t>(Register::BANK_0::INT_STATUS) | DIR_READ};
uint8_t INT_STATUS{0};
uint8_t FIFO_COUNTH{0};
uint8_t FIFO_COUNTL{0};
FIFO::DATA f[FIFO_MAX_SAMPLES] {};
};
// ensure no struct padding
static_assert(sizeof(FIFOTransferBuffer) == (4 + FIFO_MAX_SAMPLES *sizeof(FIFO::DATA)),
"Invalid FIFOTransferBuffer size");
struct register_bank0_config_t {
Register::BANK_0 reg;
uint8_t set_bits{0};
uint8_t clear_bits{0};
};
struct register_bank1_config_t {
Register::BANK_1 reg;
uint8_t set_bits{0};
uint8_t clear_bits{0};
};
struct register_bank2_config_t {
Register::BANK_2 reg;
uint8_t set_bits{0};
uint8_t clear_bits{0};
};
int probe() override;
bool Reset();
bool Configure();
void ConfigureSampleRate(int sample_rate);
void ConfigureFIFOWatermark(uint8_t samples);
void SelectRegisterBank(enum REG_BANK_SEL_BIT bank, bool force = false);
void SelectRegisterBank(Register::BANK_0 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_0); }
void SelectRegisterBank(Register::BANK_1 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_1); }
void SelectRegisterBank(Register::BANK_2 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::USER_BANK_2); }
static int DataReadyInterruptCallback(int irq, void *context, void *arg);
void DataReady();
bool DataReadyInterruptConfigure();
bool DataReadyInterruptDisable();
template <typename T> bool RegisterCheck(const T &reg_cfg);
template <typename T> uint8_t RegisterRead(T reg);
template <typename T> void RegisterWrite(T reg, uint8_t value);
template <typename T> void RegisterSetAndClearBits(T reg, uint8_t setbits, uint8_t clearbits);
template <typename T> void RegisterSetBits(T reg, uint8_t setbits) { RegisterSetAndClearBits(reg, setbits, 0); }
template <typename T> void RegisterClearBits(T reg, uint8_t clearbits) { RegisterSetAndClearBits(reg, 0, clearbits); }
uint16_t FIFOReadCount();
bool FIFORead(const hrt_abstime &timestamp_sample, uint16_t samples);
void FIFOReset();
void ProcessIMU(const hrt_abstime &timestamp_sample, const FIFO::DATA fifo[], const uint8_t samples);
void ProcessAccel(const hrt_abstime &timestamp_sample, const FIFO::DATA fifo[], const uint8_t samples);
void ProcessGyro(const hrt_abstime &timestamp_sample, const FIFO::DATA fifo[], const uint8_t samples);
bool ProcessTemperature(const FIFO::DATA fifo[], const uint8_t samples);
const spi_drdy_gpio_t _drdy_gpio;
// std::shared_ptr<PX4Accelerometer> _px4_accel;
// std::shared_ptr<PX4Gyroscope> _px4_gyro;
PX4Accelerometer _px4_accel;
PX4Gyroscope _px4_gyro;
perf_counter_t _bad_register_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad register")};
perf_counter_t _bad_transfer_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad transfer")};
perf_counter_t _fifo_empty_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO empty")};
perf_counter_t _fifo_overflow_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO overflow")};
perf_counter_t _fifo_reset_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO reset")};
perf_counter_t _drdy_missed_perf{nullptr};
hrt_abstime _reset_timestamp{0};
hrt_abstime _last_config_check_timestamp{0};
hrt_abstime _temperature_update_timestamp{0};
int _failure_count{0};
enum REG_BANK_SEL_BIT _last_register_bank {REG_BANK_SEL_BIT::USER_BANK_0};
px4::atomic<uint32_t> _drdy_fifo_read_samples{0};
bool _data_ready_interrupt_enabled{false};
enum class STATE : uint8_t {
RESET,
WAIT_FOR_RESET,
CONFIGURE,
FIFO_READ,
} _state{STATE::RESET};
uint16_t _fifo_empty_interval_us{1250}; // default 1250 us / 800 Hz transfer interval
uint32_t _fifo_gyro_samples{static_cast<uint32_t>(_fifo_empty_interval_us / (1000000 / GYRO_RATE))};
uint8_t _checked_register_bank0{0};
static constexpr uint8_t size_register_bank0_cfg{12};
register_bank0_config_t _register_bank0_cfg[size_register_bank0_cfg] {
// Register | Set bits, Clear bits
{ Register::BANK_0::INT_CONFIG, INT_CONFIG_BIT::INT1_MODE | INT_CONFIG_BIT::INT1_DRIVE_CIRCUIT, INT_CONFIG_BIT::INT1_POLARITY },
{ Register::BANK_0::FIFO_CONFIG, FIFO_CONFIG_BIT::FIFO_MODE_STOP_ON_FULL, 0 },
{ Register::BANK_0::GYRO_CONFIG0, GYRO_CONFIG0_BIT::GYRO_FS_SEL_2000_DPS | GYRO_CONFIG0_BIT::GYRO_ODR_8KHZ_SET, GYRO_CONFIG0_BIT::GYRO_ODR_8KHZ_CLEAR },
{ Register::BANK_0::ACCEL_CONFIG0, ACCEL_CONFIG0_BIT::ACCEL_FS_SEL_16G | ACCEL_CONFIG0_BIT::ACCEL_ODR_8KHZ_SET, ACCEL_CONFIG0_BIT::ACCEL_ODR_8KHZ_CLEAR },
{ Register::BANK_0::GYRO_CONFIG1, 0, GYRO_CONFIG1_BIT::GYRO_UI_FILT_ORD },
{ Register::BANK_0::GYRO_ACCEL_CONFIG0, 0, GYRO_ACCEL_CONFIG0_BIT::ACCEL_UI_FILT_BW | GYRO_ACCEL_CONFIG0_BIT::GYRO_UI_FILT_BW },
{ Register::BANK_0::ACCEL_CONFIG1, 0, ACCEL_CONFIG1_BIT::ACCEL_UI_FILT_ORD },
{ Register::BANK_0::FIFO_CONFIG1, FIFO_CONFIG1_BIT::FIFO_WM_GT_TH | FIFO_CONFIG1_BIT::FIFO_HIRES_EN | FIFO_CONFIG1_BIT::FIFO_TEMP_EN | FIFO_CONFIG1_BIT::FIFO_GYRO_EN | FIFO_CONFIG1_BIT::FIFO_ACCEL_EN, 0 },
{ Register::BANK_0::FIFO_CONFIG2, 0, 0 }, // FIFO_WM[7:0] set at runtime
{ Register::BANK_0::FIFO_CONFIG3, 0, 0 }, // FIFO_WM[11:8] set at runtime
{ Register::BANK_0::INT_CONFIG0, INT_CONFIG0_BIT::CLEAR_ON_FIFO_READ, 0 },
{ Register::BANK_0::INT_SOURCE0, INT_SOURCE0_BIT::FIFO_THS_INT1_EN, 0 },
};
uint8_t _checked_register_bank1{0};
static constexpr uint8_t size_register_bank1_cfg{4};
register_bank1_config_t _register_bank1_cfg[size_register_bank1_cfg] {
// Register | Set bits, Clear bits
{ Register::BANK_1::GYRO_CONFIG_STATIC2, 0, GYRO_CONFIG_STATIC2_BIT::GYRO_NF_DIS | GYRO_CONFIG_STATIC2_BIT::GYRO_AAF_DIS },
{ Register::BANK_1::GYRO_CONFIG_STATIC3, GYRO_CONFIG_STATIC3_BIT::GYRO_AAF_DELT_SET, GYRO_CONFIG_STATIC3_BIT::GYRO_AAF_DELT_CLEAR},
{ Register::BANK_1::GYRO_CONFIG_STATIC4, GYRO_CONFIG_STATIC4_BIT::GYRO_AAF_DELTSQR_LOW_SET, GYRO_CONFIG_STATIC4_BIT::GYRO_AAF_DELTSQR_LOW_CLEAR},
{ Register::BANK_1::GYRO_CONFIG_STATIC5, GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_BITSHIFT_SET | GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_DELTSQR_HIGH_SET, GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_BITSHIFT_CLEAR | GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_DELTSQR_HIGH_CLEAR},
};
uint8_t _checked_register_bank2{0};
static constexpr uint8_t size_register_bank2_cfg{3};
register_bank2_config_t _register_bank2_cfg[size_register_bank2_cfg] {
// Register | Set bits, Clear bits
{ Register::BANK_2::ACCEL_CONFIG_STATIC2, ACCEL_CONFIG_STATIC2_BIT::ACCEL_AAF_DELT_SET, ACCEL_CONFIG_STATIC2_BIT::ACCEL_AAF_DELT_CLEAR | ACCEL_CONFIG_STATIC2_BIT::ACCEL_AAF_DIS },
{ Register::BANK_2::ACCEL_CONFIG_STATIC3, ACCEL_CONFIG_STATIC3_BIT::ACCEL_AAF_DELTSQR_LOW_SET, ACCEL_CONFIG_STATIC3_BIT::ACCEL_AAF_DELTSQR_LOW_CLEAR },
{ Register::BANK_2::ACCEL_CONFIG_STATIC4, ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_BITSHIFT_SET | ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_DELTSQR_HIGH_SET, ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_BITSHIFT_CLEAR | ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_DELTSQR_HIGH_CLEAR },
};
uint32_t _temperature_samples{0};
// Support for the IMU server
uint32_t _imu_server_index{0};
uint32_t _imu_server_decimator{0};
imu_server_s _imu_server_data;
uORB::Publication<imu_server_s> _imu_server_pub{ORB_ID(imu_server)};
};
@@ -0,0 +1,430 @@
/****************************************************************************
*
* 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file InvenSense_ICM42688P_registers.hpp
*
* Invensense ICM-42688-P registers.
*
*/
#pragma once
#include <cstdint>
namespace InvenSense_ICM42688P
{
// TODO: move to a central header
static constexpr uint8_t Bit0 = (1 << 0);
static constexpr uint8_t Bit1 = (1 << 1);
static constexpr uint8_t Bit2 = (1 << 2);
static constexpr uint8_t Bit3 = (1 << 3);
static constexpr uint8_t Bit4 = (1 << 4);
static constexpr uint8_t Bit5 = (1 << 5);
static constexpr uint8_t Bit6 = (1 << 6);
static constexpr uint8_t Bit7 = (1 << 7);
static constexpr uint32_t SPI_SPEED = 24 * 1000 * 1000; // 24 MHz SPI
static constexpr uint8_t DIR_READ = 0x80;
static constexpr uint8_t WHOAMI = 0x47;
static constexpr float TEMPERATURE_SENSITIVITY = 132.48f; // LSB/C
static constexpr float TEMPERATURE_OFFSET = 25.f; // C
namespace Register
{
enum class BANK_0 : uint8_t {
DEVICE_CONFIG = 0x11,
INT_CONFIG = 0x14,
FIFO_CONFIG = 0x16,
TEMP_DATA1 = 0x1D,
TEMP_DATA0 = 0x1E,
INT_STATUS = 0x2D,
FIFO_COUNTH = 0x2E,
FIFO_COUNTL = 0x2F,
FIFO_DATA = 0x30,
SIGNAL_PATH_RESET = 0x4B,
INTF_CONFIG0 = 0x4C,
INTF_CONFIG1 = 0x4D,
PWR_MGMT0 = 0x4E,
GYRO_CONFIG0 = 0x4F,
ACCEL_CONFIG0 = 0x50,
GYRO_CONFIG1 = 0x51,
GYRO_ACCEL_CONFIG0 = 0x52,
ACCEL_CONFIG1 = 0x53,
FIFO_CONFIG1 = 0x5F,
FIFO_CONFIG2 = 0x60,
FIFO_CONFIG3 = 0x61,
INT_CONFIG0 = 0x63,
INT_SOURCE0 = 0x65,
SELF_TEST_CONFIG = 0x70,
WHO_AM_I = 0x75,
REG_BANK_SEL = 0x76,
};
enum class BANK_1 : uint8_t {
GYRO_CONFIG_STATIC2 = 0x0B,
GYRO_CONFIG_STATIC3 = 0x0C,
GYRO_CONFIG_STATIC4 = 0x0D,
GYRO_CONFIG_STATIC5 = 0x0E,
INTF_CONFIG5 = 0x7B,
};
enum class BANK_2 : uint8_t {
ACCEL_CONFIG_STATIC2 = 0x03,
ACCEL_CONFIG_STATIC3 = 0x04,
ACCEL_CONFIG_STATIC4 = 0x05,
};
};
//---------------- BANK0 Register bits
// DEVICE_CONFIG
enum DEVICE_CONFIG_BIT : uint8_t {
SOFT_RESET_CONFIG = Bit0, //
};
// INT_CONFIG
enum INT_CONFIG_BIT : uint8_t {
INT1_MODE = Bit2,
INT1_DRIVE_CIRCUIT = Bit1,
INT1_POLARITY = Bit0,
};
// FIFO_CONFIG
enum FIFO_CONFIG_BIT : uint8_t {
// 7:6 FIFO_MODE
FIFO_MODE_STOP_ON_FULL = Bit7 | Bit6, // 11: STOP-on-FULL Mode
};
// INT_STATUS
enum INT_STATUS_BIT : uint8_t {
RESET_DONE_INT = Bit4,
DATA_RDY_INT = Bit3,
FIFO_THS_INT = Bit2,
FIFO_FULL_INT = Bit1,
};
// SIGNAL_PATH_RESET
enum SIGNAL_PATH_RESET_BIT : uint8_t {
ABORT_AND_RESET = Bit3,
FIFO_FLUSH = Bit1,
};
// PWR_MGMT0
enum PWR_MGMT0_BIT : uint8_t {
GYRO_MODE_LOW_NOISE = Bit3 | Bit2, // 11: Places gyroscope in Low Noise (LN) Mode
ACCEL_MODE_LOW_NOISE = Bit1 | Bit0, // 11: Places accelerometer in Low Noise (LN) Mode
};
// GYRO_CONFIG0
enum GYRO_CONFIG0_BIT : uint8_t {
// 7:5 GYRO_FS_SEL
GYRO_FS_SEL_2000_DPS = 0, // 0b000 = ±2000dps (default)
GYRO_FS_SEL_1000_DPS = Bit5,
GYRO_FS_SEL_500_DPS = Bit6,
GYRO_FS_SEL_250_DPS = Bit6 | Bit5,
GYRO_FS_SEL_125_DPS = Bit7,
// 3:0 GYRO_ODR
// 0001: 32kHz
GYRO_ODR_32KHZ_SET = Bit0,
GYRO_ODR_32KHZ_CLEAR = Bit3 | Bit2 | Bit0,
// 0010: 16kHz
GYRO_ODR_16KHZ_SET = Bit1,
GYRO_ODR_16KHZ_CLEAR = Bit3 | Bit2 | Bit0,
// 0011: 8kHz
GYRO_ODR_8KHZ_SET = Bit1 | Bit0,
GYRO_ODR_8KHZ_CLEAR = Bit3 | Bit2,
// 0110: 1kHz (default)
GYRO_ODR_1KHZ_SET = Bit2 | Bit1,
GYRO_ODR_1KHZ_CLEAR = Bit3 | Bit0,
};
// ACCEL_CONFIG0
enum ACCEL_CONFIG0_BIT : uint8_t {
// 7:5 ACCEL_FS_SEL
ACCEL_FS_SEL_16G = 0, // 000: ±16g (default)
ACCEL_FS_SEL_8G = Bit5,
ACCEL_FS_SEL_4G = Bit6,
ACCEL_FS_SEL_2G = Bit6 | Bit5,
// 3:0 ACCEL_ODR
// 0001: 32kHz
ACCEL_ODR_32KHZ_SET = Bit0,
ACCEL_ODR_32KHZ_CLEAR = Bit3 | Bit2 | Bit0,
// 0010: 16kHz
ACCEL_ODR_16KHZ_SET = Bit1,
ACCEL_ODR_16KHZ_CLEAR = Bit3 | Bit2 | Bit0,
// 0011: 8kHz
ACCEL_ODR_8KHZ_SET = Bit1 | Bit0,
ACCEL_ODR_8KHZ_CLEAR = Bit3 | Bit2,
// 0110: 1kHz (default)
ACCEL_ODR_1KHZ_SET = Bit2 | Bit1,
ACCEL_ODR_1KHZ_CLEAR = Bit3 | Bit0,
};
// GYRO_CONFIG1
enum GYRO_CONFIG1_BIT : uint8_t {
GYRO_UI_FILT_ORD = Bit3 | Bit2, // 00: 1st Order
};
// GYRO_ACCEL_CONFIG0
enum GYRO_ACCEL_CONFIG0_BIT : uint8_t {
// 7:4 ACCEL_UI_FILT_BW
ACCEL_UI_FILT_BW = Bit7 | Bit6 | Bit5 | Bit4, // 0: BW=ODR/2
// 3:0 GYRO_UI_FILT_BW
GYRO_UI_FILT_BW = Bit3 | Bit2 | Bit1 | Bit0, // 0: BW=ODR/2
};
// ACCEL_CONFIG1
enum ACCEL_CONFIG1_BIT : uint8_t {
ACCEL_UI_FILT_ORD = Bit4 | Bit3, // 00: 1st Order
};
// FIFO_CONFIG1
enum FIFO_CONFIG1_BIT : uint8_t {
FIFO_RESUME_PARTIAL_RD = Bit6,
FIFO_WM_GT_TH = Bit5,
FIFO_HIRES_EN = Bit4,
FIFO_TEMP_EN = Bit2,
FIFO_GYRO_EN = Bit1,
FIFO_ACCEL_EN = Bit0,
};
// INT_CONFIG0
enum INT_CONFIG0_BIT : uint8_t {
// 3:2 FIFO_THS_INT_CLEAR
CLEAR_ON_FIFO_READ = Bit3,
};
// INT_SOURCE0
enum INT_SOURCE0_BIT : uint8_t {
UI_FSYNC_INT1_EN = Bit6,
PLL_RDY_INT1_EN = Bit5,
RESET_DONE_INT1_EN = Bit4,
UI_DRDY_INT1_EN = Bit3,
FIFO_THS_INT1_EN = Bit2, // FIFO threshold interrupt routed to INT1
FIFO_FULL_INT1_EN = Bit1,
UI_AGC_RDY_INT1_EN = Bit0,
};
// REG_BANK_SEL
enum REG_BANK_SEL_BIT : uint8_t {
USER_BANK_0 = 0, // 0: Select USER BANK 0.
USER_BANK_1 = Bit0, // 1: Select USER BANK 1.
USER_BANK_2 = Bit1, // 2: Select USER BANK 2.
USER_BANK_3 = Bit1 | Bit0, // 3: Select USER BANK 3.
};
//---------------- BANK1 Register bits
// GYRO_CONFIG_STATIC2
enum GYRO_CONFIG_STATIC2_BIT : uint8_t {
GYRO_AAF_DIS = Bit1,
GYRO_NF_DIS = Bit0,
};
// GYRO_CONFIG_STATIC3
enum GYRO_CONFIG_STATIC3_BIT : uint8_t {
// 585 Hz
GYRO_AAF_DELT_SET = Bit3 | Bit2 | Bit0, //13
GYRO_AAF_DELT_CLEAR = Bit5 | Bit4 | Bit1,
// 213 Hz
// GYRO_AAF_DELT_SET = Bit2 | Bit0, //5
// GYRO_AAF_DELT_CLEAR = Bit5 | Bit4 | Bit3 | Bit1,
// 126 Hz
//GYRO_AAF_DELT_SET = Bit1 | Bit0, //3
//GYRO_AAF_DELT_CLEAR = Bit5 | Bit4 | Bit3 | Bit2,
// 42 Hz
// GYRO_AAF_DELT_SET = Bit0, //1
// GYRO_AAF_DELT_CLEAR = Bit5 | Bit4 | Bit3 | Bit2 | Bit1,
};
// GYRO_CONFIG_STATIC4
enum GYRO_CONFIG_STATIC4_BIT : uint8_t {
// 585 Hz
GYRO_AAF_DELTSQR_LOW_SET = Bit7 | Bit5 | Bit3 | Bit1, //170
GYRO_AAF_DELTSQR_LOW_CLEAR = Bit6 | Bit4 | Bit2 | Bit0,
// 213 Hz
// GYRO_AAF_DELTSQR_LOW_SET = Bit4 | Bit3 | Bit0, //25
// GYRO_AAF_DELTSQR_LOW_CLEAR = Bit7 | Bit6 | Bit5 | Bit2 | Bit1,
// 126 Hz
//GYRO_AAF_DELTSQR_LOW_SET = Bit3 | Bit0, //9
//GYRO_AAF_DELTSQR_LOW_CLEAR = Bit7 | Bit6 | Bit5 | Bit4 | Bit2 | Bit1,
// 42 Hz
// GYRO_AAF_DELTSQR_LOW_SET = Bit0, //1
// GYRO_AAF_DELTSQR_LOW_CLEAR = Bit7 | Bit6 | Bit5 | Bit4 | Bit3 | Bit2 | Bit1,
};
// GYRO_CONFIG_STATIC5
enum GYRO_CONFIG_STATIC5_BIT : uint8_t {
// 585 Hz
GYRO_AAF_DELTSQR_HIGH_SET = 0,
GYRO_AAF_DELTSQR_HIGH_CLEAR = Bit3 | Bit2 | Bit1 | Bit0,
GYRO_AAF_BITSHIFT_SET = Bit7, // 8 << 4
GYRO_AAF_BITSHIFT_CLEAR = Bit6 | Bit5 | Bit4,
// 213 Hz
// GYRO_AAF_DELTSQR_HIGH_SET = 0,
// GYRO_AAF_DELTSQR_HIGH_CLEAR = Bit3 | Bit2 | Bit1 | Bit0,
// GYRO_AAF_BITSHIFT_SET = Bit7 | Bit5, //10
// GYRO_AAF_BITSHIFT_CLEAR = Bit6 | Bit4,
// 126 Hz
// GYRO_AAF_BITSHIFT_SET = Bit7 | Bit6, //12
// GYRO_AAF_BITSHIFT_CLEAR = Bit5 | Bit4,
// 42 Hz
// GYRO_AAF_BITSHIFT_SET = Bit7 | Bit6 | Bit5 | Bit4, //15
// GYRO_AAF_BITSHIFT_CLEAR = 0,
};
//---------------- BANK2 Register bits
// ACCEL_CONFIG_STATIC2
enum ACCEL_CONFIG_STATIC2_BIT : uint8_t {
ACCEL_AAF_DIS = Bit0,
ACCEL_AAF_DELT = Bit3 | Bit1,
// 213 Hz
ACCEL_AAF_DELT_SET = Bit3 | Bit1, //5
ACCEL_AAF_DELT_CLEAR = Bit6 | Bit5 | Bit4 | Bit2,
// 42 Hz
// ACCEL_AAF_DELT_SET = Bit1, //1
// ACCEL_AAF_DELT_CLEAR = Bit6 | Bit5 | Bit4 | Bit3 | Bit2,
};
// ACCEL_CONFIG_STATIC3
enum ACCEL_CONFIG_STATIC3_BIT : uint8_t {
ACCEL_AAF_DELTSQR_LOW = Bit4 | Bit3 | Bit0,
// 213 Hz
ACCEL_AAF_DELTSQR_LOW_SET = Bit4 | Bit3 | Bit0, //25
ACCEL_AAF_DELTSQR_LOW_CLEAR = Bit7 | Bit6 | Bit5 | Bit2 | Bit1,
// 42 Hz
// ACCEL_AAF_DELTSQR_LOW_SET = Bit0, //1
// ACCEL_AAF_DELTSQR_LOW_CLEAR = Bit7 | Bit6 | Bit5 | Bit4 | Bit3 | Bit2 | Bit1,
};
// ACCEL_CONFIG_STATIC4
enum ACCEL_CONFIG_STATIC4_BIT : uint8_t {
ACCEL_AAF_BITSHIFT = Bit7 | Bit5,
ACCEL_AAF_DELTSQR_HIGH = 0,
// 213 Hz
ACCEL_AAF_BITSHIFT_SET = Bit7 | Bit5, //10
ACCEL_AAF_BITSHIFT_CLEAR = Bit6 | Bit4,
// 42 Hz
// ACCEL_AAF_BITSHIFT_SET = Bit7 | Bit6 | Bit5 | Bit4, //15
// ACCEL_AAF_BITSHIFT_CLEAR = 0,
ACCEL_AAF_DELTSQR_HIGH_SET = 0,
ACCEL_AAF_DELTSQR_HIGH_CLEAR = Bit3 | Bit2 | Bit1 | Bit0,
};
namespace FIFO
{
static constexpr size_t SIZE = 2048;
// FIFO_DATA layout when FIFO_CONFIG1 has FIFO_GYRO_EN and FIFO_ACCEL_EN set
// Packet 4
struct DATA {
uint8_t FIFO_Header;
uint8_t ACCEL_DATA_X1; // Accel X [19:12]
uint8_t ACCEL_DATA_X0; // Accel X [11:4]
uint8_t ACCEL_DATA_Y1; // Accel Y [19:12]
uint8_t ACCEL_DATA_Y0; // Accel Y [11:4]
uint8_t ACCEL_DATA_Z1; // Accel Z [19:12]
uint8_t ACCEL_DATA_Z0; // Accel Z [11:4]
uint8_t GYRO_DATA_X1; // Gyro X [19:12]
uint8_t GYRO_DATA_X0; // Gyro X [11:4]
uint8_t GYRO_DATA_Y1; // Gyro Y [19:12]
uint8_t GYRO_DATA_Y0; // Gyro Y [11:4]
uint8_t GYRO_DATA_Z1; // Gyro Z [19:12]
uint8_t GYRO_DATA_Z0; // Gyro Z [11:4]
uint8_t TEMP_DATA1; // Temperature[15:8]
uint8_t TEMP_DATA0; // Temperature[7:0]
uint8_t TimeStamp_h; // TimeStamp[15:8]
uint8_t TimeStamp_l; // TimeStamp[7:0]
uint8_t Ext_Accel_X_Gyro_X; // Accel X [3:0] Gyro X [3:0]
uint8_t Ext_Accel_Y_Gyro_Y; // Accel Y [3:0] Gyro Y [3:0]
uint8_t Ext_Accel_Z_Gyro_Z; // Accel Z [3:0] Gyro Z [3:0]
};
// With FIFO_ACCEL_EN and FIFO_GYRO_EN header should be 8b_0110_10xx
enum FIFO_HEADER_BIT : uint8_t {
HEADER_MSG = Bit7, // 1: FIFO is empty
HEADER_ACCEL = Bit6, // 1: Packet is sized so that accel data have location in the packet, FIFO_ACCEL_EN must be 1
HEADER_GYRO = Bit5, // 1: Packet is sized so that gyro data have location in the packet, FIFO_GYRO_EN must be1
HEADER_20 = Bit4, // 1: Packet has a new and valid sample of extended 20-bit data for gyro and/or accel
HEADER_TIMESTAMP_FSYNC = Bit3 | Bit2,
HEADER_ODR_ACCEL = Bit1, // 1: The ODR for accel is different for this accel data packet compared to the previous accel packet
HEADER_ODR_GYRO = Bit0, // 1: The ODR for gyro is different for this gyro data packet compared to the previous gyro packet
};
}
} // namespace InvenSense_ICM42688P
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2024 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
@@ -31,57 +31,56 @@
*
****************************************************************************/
#include "mmc5983ma.h"
#include "ICM42688P.hpp"
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/module.h>
#include <string>
I2CSPIDriverBase *MMC5983MA::instantiate(const I2CSPIDriverConfig &config, int runtime_instance)
void ICM42688P::print_usage()
{
device::Device *interface = MMC5983MA_I2C_interface(config);
if (interface == nullptr) {
PX4_ERR("alloc failed");
return nullptr;
}
if (interface->init() != OK) {
delete interface;
PX4_DEBUG("no device on bus %i (devid 0x%x)", config.bus, config.spi_devid);
return nullptr;
}
MMC5983MA *dev = new MMC5983MA(interface, config);
if (dev == nullptr) {
delete interface;
return nullptr;
}
if (OK != dev->init()) {
delete dev;
return nullptr;
}
return dev;
}
void MMC5983MA::print_usage()
{
PRINT_MODULE_USAGE_NAME("mmc5983ma", "driver");
PRINT_MODULE_USAGE_SUBCATEGORY("magnetometer");
PRINT_MODULE_USAGE_NAME("icm42688p", "driver");
PRINT_MODULE_USAGE_SUBCATEGORY("imu");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x30);
PRINT_MODULE_USAGE_COMMAND("reset");
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true);
PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true);
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
}
extern "C" int mmc5983ma_main(int argc, char *argv[])
// I2CSPIDriverBase *ICM42688P::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
// int runtime_instance)
// {
// ICM42688P *instance = new ICM42688P(iterator.configuredBusOption(), iterator.bus(), iterator.devid(), cli.rotation,
// cli.bus_frequency, cli.spi_mode, iterator.DRDYGPIO());
//
// if (!instance) {
// PX4_ERR("alloc failed");
// return nullptr;
// }
//
// if (OK != instance->init()) {
// delete instance;
// return nullptr;
// }
//
// return instance;
// }
extern "C" int icm42688p_main(int argc, char *argv[])
{
using ThisDriver = MMC5983MA;
for (int i = 0; i <= argc - 1; i++) {
if (std::string(argv[i]) == "-h") {
argv[i] = 0;
hitl_mode = true;
break;
}
}
int ch;
BusCLIArguments cli{true, false};
cli.i2c_address = 0x30;
cli.default_i2c_frequency = 400000;
using ThisDriver = ICM42688P;
BusCLIArguments cli{false, true};
cli.default_spi_frequency = SPI_SPEED;
while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) {
switch (ch) {
@@ -98,7 +97,7 @@ extern "C" int mmc5983ma_main(int argc, char *argv[])
return -1;
}
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_MAG_DEVTYPE_MMC5983MA);
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_IMU_DEVTYPE_ICM42688P);
if (!strcmp(verb, "start")) {
return ThisDriver::module_start(cli, iterator);
-34
View File
@@ -1,34 +0,0 @@
############################################################################
#
# Copyright (c) 2024 ModalAI, Inc. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include_directories(${PX4_BOARD_DIR}/libfc-sensor-api/inc)
@@ -1,7 +1,7 @@
# Link against the public stub version of the proprietary fc sensor library
target_link_libraries(px4 PRIVATE
${PX4_BOARD_DIR}/libfc-sensor-api/build/libfc_sensor.so
${PX4_SOURCE_DIR}/src//modules/muorb/apps/libfc-sensor-api/build/libfc_sensor.so
px4_layer
${module_libraries}
)

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