Compare commits

...

120 Commits

Author SHA1 Message Date
Christian Rauch 437b6b9844 remove unused debug.h 2023-08-14 11:03:24 -04:00
Christian Rauch 43ec73165f BMI0xx: remove unused board_dma_alloc.h 2023-08-14 11:03:24 -04:00
Christian Rauch ecbbaeb457 ADIS16497: replace NuttX specific up_udelay with HAL version px4_udelay 2023-08-14 11:03:24 -04:00
Christian Rauch 345d814ca4 enable common barometer, IMU and magnetometer 2023-08-14 11:03:24 -04:00
Christian Rauch c2b10ced8d linux_pwm_out must link mixer_module 2023-08-14 10:52:37 -04:00
Christian Rauch 2bcb3ea3f7 skip SSH key check for simpler builds in the Docker container 2023-08-14 10:50:28 -04:00
bresch dcb4c182fe ekf2: stop GNSS fusion when fix is loss 2023-07-21 10:21:57 +02:00
Matthias Grob 5736a31a67 rc.interface: explicitly save empty ESC mask 2023-07-13 16:27:38 +02:00
Mathieu Bresciani cc26cf4121 mc_pos_control: fix potential thrust spike on hover thrust change
Co-authored-by: Josh Henderson <hendjoshsr71@gmail.com>
Co-authored-by: Matthias Grob <maetugr@gmail.com>
2023-06-16 15:52:52 +02:00
Beat Küng 504d951c75 fix kconfig: rename LINUX to LINUX_TARGET
LINUX is defined by cmake >= 3.25:
https://cmake.org/cmake/help/latest/variable/LINUX.html
2023-04-21 07:42:20 +02:00
David Sidrane 1c8ab2a0d7
[BACKPORT] px4_fmu-v6c:Add Mini & fix Rev 1 (#21227) 2023-03-06 12:21:07 -08:00
Julian Oes 6d27784013 nuttx: update submodule to clean backport branch
This should be identical but now cleanly pointing to the
px4_firmware_nuttx-10.1.0+ branch.
2023-03-02 03:53:29 -08:00
David Sidrane a8f29bc2aa
px4_fmu-v6x:Fix CUAV Sensor Set startup (#21221)
Reverts part of 3c10e34a49 not
   applicable to V1.13 VER/REV system.
2023-03-01 09:15:03 -08:00
Beat Küng 4bcbfec6cb nuttx: update submodule (DMA + mmcsd fixes) 2023-02-22 06:32:16 +13:00
Leonardo Garcia c7b9e160b8
mro/pixracerpro: add missing px4_platform_configure() call (#21161) 2023-02-21 09:30:59 +01:00
alexklimaj 5334ec1ef0 Move uavcan start to end of rcS to prevent sd card read lock 2023-02-13 22:34:58 -05:00
alexklimaj 486674a652 Add ARK PAB Carrier
Add ARK_FMU_V6X to RCS netman

Remove arkv6x rc single wire

Fix arkv6x mtd

arkv6x bootloader init all pins to prevent power cycling peripherals on boot

arkv6x don't power cycle sd card on boot

arkv6x add UART4 Telem 4
2023-02-13 22:34:58 -05:00
alexklimaj 6af8e34596 boards: arkv6x add pulldowns to GPIO pins UART7 RTS and UART7 CTS 2023-02-13 22:34:58 -05:00
FriedrichTuttas ec06fae3fd boards: px4_fmu-v6x add pulldowns to GPIO pins UART7 RTS and UART7 CTS (#20974)
- https://github.com/PX4/PX4-Autopilot/issues/20762

Co-authored-by: David Sidrane <David.Sidrane@Nscdg.com>
2023-02-07 22:29:52 -05:00
Daniel Agar 7001d90d84
lib/sensor_calibration: BiasCorrectedSensorOffset() don't incorporate thermal offsets
- the thermal offsets are an optional correction applied to the raw data, so when updating an existing calibration offset with new learned bias we don't want this incorporated
2023-02-07 09:12:09 -05:00
CUAVmengxiao ca9af1ca9e
drivers: add support for ICP101XX and ICP201XX 2023-02-06 15:19:49 -05:00
Ryan Meagher 7a6cfce0ca
drivers/barometer/invensense: fix icp10111 and icp10100
* fix icp so it compiles
* add icp10111 and icp10100 DEVTPYE
2023-02-06 15:19:39 -05:00
David Sidrane 3c10e34a49
fmu-v6x:CUAV HW Version changes 2023-02-06 15:17:32 -05:00
CUAVmengxiao 58cc105493
px4_fmu-v6X: add CUAV board 2023-02-06 15:16:28 -05:00
Thomas Watson 9cf38206f6
boards/mro/pixracerpro: fix voltage/current monitoring
This corrects the board definition to use the proper polarity
for the brick power valid signal, thus allowing the board to
detect the battery and monitor it properly.
2023-02-06 15:13:25 -05:00
Claudio 2295ee9164
msg/tools/generate_microRTPS_bridge.py allow ROS2 distro humble
Co-authored-by: Claudio Fritsche <claudio@onesecdelivery.com>
2023-01-23 09:48:24 -05:00
Julian Oes 37cb24afd8 mavlink_shell: fix stall on CubeOrange
On CubeOrange where no console is configured by default, starting
MAVLink shell just stalls, and doesn't work.

Also, logfile download has been reported not to work, and again, seems
to work with this change.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-01-04 22:33:36 -05:00
Beat Küng 985482badb mixer_module: only advertise actuator_outputs when mixer is loaded 2022-12-16 07:50:57 +01:00
bresch beddb3969e GyroCalibration: update sensor correction before using it
Otherwise, the thermal offset value can be outdated
2022-11-23 14:25:31 -05:00
bresch 4481c3bc1f TC: erase current calibration when temp cal is completed 2022-11-23 14:25:31 -05:00
Julian Oes 46a12a09bf fmu-v2: make optional sensor startup quiet
Signed-off-by: Julian Oes <julian@oes.ch>
2022-11-22 21:12:09 +13:00
bresch 72becdf407 ekf2: do not fuse ZVU if other velocity source is active 2022-11-15 13:11:06 -05:00
Matthias Grob 228def6081 mission_block: explicitly (re)set the acceptance radius to default for takeoff items
otherwise a previously adjusted or uninitialized radius from the last flight
can cause problems during the new takeoff
2022-11-11 14:48:45 +13:00
Matthias Grob 092562dc51 mission_block: minimal acceptance radius of 1mm
to avoid float rounding errors leading to tiny acceptance radii
getting considered
2022-11-11 14:48:45 +13:00
Daniel Agar 9fdf5ada40
boards: px4_fmu-v6x_default include systemcmds/gpio 2022-11-07 17:11:28 -05:00
Daniel Agar 872ac68daf
vehicle_magnetometer: fix standalone mag bias est factored into in flight mag cal
- preflight mag bias estimate is in the vehicle body frame and removed from the raw mag data after it's rotated, calibrated, etc
 - in flight mag bias (from ekf2) is in the vehicle body frame, but stored as a sensor frame offset immediately
2022-11-07 09:31:49 -05:00
David Sidrane b46c608f6e px4_fmu-v6:Add Revision 1 to manifest to note I2C4 is only internal 2022-11-03 07:32:40 +13:00
Julian Oes 37cf8024c3 Holybro PX4Vision: Don't use IO 2022-11-03 07:32:25 +13:00
Silvan Fuhrer 65d22120b2 Navigator: initialize _mission_item for all navigation modes in Navigator::Navigator()
This fixes the issue where the init happended in the initializer list, at which point
the params were not yet initialized and thus resulted in random values for the init
values of _mission_item.loiter_radius and .acceptance_radius.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-10-27 13:20:29 +02:00
Thomas Stastny dc7f29e2ec
welford mean: protect against negative variances 2022-10-05 10:29:03 -04:00
Thomas Stastny fbef296890
welford mean: convert to matrix only template 2022-10-05 10:29:03 -04:00
Daniel Agar 6ce38b8296
vehicle_imu: only reset raw accel/gyro Welford mean periodically
- vehicle_imu_status can publish immediately on any measured sample
rate change or sensor error increment, but the windowed mean/variance
shouldn't necessarily reset that often
2022-10-05 10:29:03 -04:00
Julian Oes e3d730ea37 ms5611: ignore reading 0
This prevents publishing a negative pressure which leads to a NAN
altitude estimate further down the line.
2022-10-04 09:42:16 -04:00
alexklimaj d22d33e936 Fix ARKV6X control allocator with base boards 2022-09-29 14:24:20 -04:00
bresch 1ea4fe9b7b
Mag: fix estimated bias save to calibration
Clear the calibration at the end only otherwise everything gets erased
at the end of the first iteration of the outer loop
2022-09-28 10:03:35 -04:00
Julian Oes 2e7df77bff uavcan: fix RTCM corrections publication
Before this fix, this function would stall and somehow never return.
2022-09-27 22:01:48 -04:00
Julian Oes 241abb933a libuavcan: update submodule
This fixes a Python 3.10 issue for me.
2022-09-27 21:55:08 -04:00
Julian Oes 02c281c3e8 fmu-v5x: support for mini base board
This was forgotton with all the merges and shuffling previously.
2022-09-27 05:45:22 +13:00
Julian Oes 280f2e3abc fmu-v3: make optional sensor startup quiet
This fixes the errors showing up at startup for me with a Black Cube.
2022-09-27 05:45:22 +13:00
Julian Oes 22f338b58c fmu-v6x: alias, add VX43
- alias from hw_mft_list_v0650 to hw_mft_list_v0600 as it is the same
- add V6X50 again
2022-09-27 05:45:22 +13:00
Julian Oes 5b60985494 fmu-v5x: alias for duplicates, remove commented
- Removed commented out config data.
- hw_mft_list_v0540 was the same as hw_mft_list_v0500
2022-09-27 05:45:22 +13:00
Julian Oes 51607928c0 fmu-v6: disable Rev 0, Rev 1 for HB Mini, and CM4
As I understand it, only Rev 3 and Rev 4 were shipped by HB for Mini and
CM4, and are likely to be used for it.

It would be nice to have all combinations but it requires quite some
flash in the current implementation.
2022-09-27 05:45:22 +13:00
Julian Oes 426d13a82e fmu-v5x: disable rev0 for HB Mini and CM4 base
As I understand it, only Rev 1 and Rev 2 were shipped by HB, and likely
to be used for the Mini and CM4.
2022-09-27 05:45:22 +13:00
Julian Oes 90c0d77c7b platforms: decrease flash usage by type for bus id
My assumption is that the bus are numbered < 127.
This saves about 100 bytes of flash.
2022-09-27 05:45:22 +13:00
vincentpoont2 fdc7ee3674 update fmu-v6x rc.board_sensors, add V6X004003 2022-09-27 05:45:22 +13:00
vincentpoont2 eef7b35747 update fmuv5x rc.board_sensors with V5X004000 2022-09-27 05:45:22 +13:00
Vincent Poon 65b1370ad1 update v5x rc.board_sensors
add V5X004002
2022-09-27 05:45:22 +13:00
Vincentpoont2 0e0324de5d Correct BOARD_NUM_SPI_CFG_HW_VERSIONS at board_config.h 2022-09-27 05:45:22 +13:00
Vincentpoont2 73e6660411 Fix Error on manifest.c 2022-09-27 05:45:22 +13:00
Vincentpoont2 7ff373fee2 Fix Error on board_config.h Define on FMUv5X & FMUv6X 2022-09-27 05:45:22 +13:00
Vincentpoont2 f4a5c71ccd Add Holybro Pixhawk Pi CM4 Baseboard Support 2022-09-27 05:45:22 +13:00
Julian Oes 3ccde2f4db cuav_x7pro: save flash on test target 2022-09-23 20:55:41 +12:00
Julian Oes dbf1f31bec boards/platform: remove confusing override
This removes the odd px4_i2c_bus_external override which was confusing
me and lead to odd and inconsistent results.

The function is now only available with an int as the argument.
2022-09-23 20:55:41 +12:00
alexklimaj 61d2b13e43 Add BMP390 to BMP388 driver 2022-09-20 20:34:23 -04:00
Julian Oes 8cfc4fc7ca boards: save some flash on CubeOrange test config 2022-09-20 18:56:04 -04:00
vincentpoont2 ebc67464c3 Add PX4 vision v1.5 Airframe 2022-09-20 18:56:04 -04:00
Daniel Agar a5a9b1011a [DO NOT MERGE] px4_i2c_device_external hacks 2022-09-20 18:54:28 -04:00
Julian Oes 1ad71eefa1 px4_fmu-v6c: Move I2C 4 back to External
This is a revert of the revert.
This reverts commit 1080855f4d.
2022-09-20 18:54:28 -04:00
Julian Oes 7786bf6dbc fmu-v6c: internal baro and mag on external bus
This swaps the internal baro and mag back to the bus which is both
internal an external but configured as external for this case.
2022-09-20 18:54:28 -04:00
Alex Klimaj af0d53cdc9
boards: V1.13.0 ARKV6X Backport (#20253) 2022-09-20 18:53:48 -04:00
RomanBapst 79367ed417 standard: fixed pusher assist in hover
- in hover mode the pusher assist is already set in update_mc_state()

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-09-15 13:07:27 -04:00
David Sidrane 417c973cc9 px4_fmu-v6x:HB Mini add Ver 3, Ver 4 init 2022-09-09 15:43:10 +12:00
Daniel Agar 26f912eb8a icm42670p run at full speed 2022-09-06 16:23:14 +12:00
Daniel Agar e7d18960a5 drivers/imu/invensense/icm42670p: cleanup and small fixes 2022-09-06 16:23:14 +12:00
Daniel Agar 8a54b21e7d
adis16470: fix accel and gyro scaling 2022-08-17 11:40:30 -04:00
RomanBapst baab4501f6
gps_inject_data: fixed integer overflow
- array length of data was increased without changing the data type of
the variable holding the length

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2022-07-13 11:20:35 -04:00
bresch b30c2c22b3
ekf2: do not run rng kinematic consistency check for fixed-wings
As they are always moving horizontally, the check doesn't make sense
for fixed-wings.
Also don't run the check while on ground to prevent getting a failed
check during pre-takeoff manipulation.
2022-07-12 13:54:30 -04:00
Daniel Agar cc7e709597
uavcan: GNSS optionally publish RTCMStream or MovingBaselineData 2022-07-12 13:54:21 -04:00
Daniel Agar 416610afc3
differential_pressure/sdp3x: sdp3x_main fix 'keep running' regression 2022-07-12 13:54:11 -04:00
David Sidrane 841797da2a
px4_fmu-v6X:Added Holybro mini base board 2022-07-01 15:33:08 -04:00
David Sidrane 55706108b6
uc_stm32h7_can:Correct initalization of the mumber of interfaces
H7 Only supports 2 not 3 CAN interfaces.

   CanInitHelper passes in in the run time configuration of
   the number of interfaces. The code was ignoring these!
2022-07-01 15:32:53 -04:00
David Sidrane e1f86f510b
px4_fmu-v5X:Added Holybro mini base board 2022-07-01 15:32:44 -04:00
David Sidrane 17ef175402
px4_fmu-v6x:Add Rev 4 Sensors 2022-07-01 15:32:09 -04:00
Alex Klimaj f9980e0721
uavcannode: Fix dronecan baro units 2022-06-17 14:44:32 -04:00
Daniel Agar 6823cbc414
sensors/vehicle_angular_velocity: add IMU_GYRO_RATEMAX constraints 2022-06-07 16:23:01 -04:00
Daniel Agar beaebe4d0b
sensors/vehicle_imu: don't bother checking IMU_GYRO_RATEMAX 2022-06-07 16:22:54 -04:00
Daniel Agar 0bddca6b9b
boards: NuttX update all boards to preallocated sem holder list
- CONFIG_SEM_PREALLOCHOLDERS=32
 - CONFIG_SEM_NNESTPRIO=16 (default)
2022-05-29 13:49:01 -04:00
Daniel Agar c50c1e3982
update NuttX and apps to latest with sem holder fixes and updated ostest 2022-05-29 13:48:15 -04:00
Daniel Agar a249b77647
boards: reduce SPI DMA buffers on older STM32F4 boards
- on common IMUs like the mpu6000, mpu9250, icm20602, etc each FIFO
sample is only 12 bytes so this is still more than large enough for the
worst case transfer
2022-05-27 16:28:26 -04:00
Daniel Agar 17de164e95
boards: pixhawk 2 cube skip starting low quality l3gd20 gyro to save memory and cpu
- free memory is getting tight on these older boards (depending on
configuratoin) and the pixhawk 2 cube still has 2 other superior IMUs, so this is just
dropping dead weight
2022-05-27 16:28:22 -04:00
David Sidrane a057b38c40
Update all H7 Bootloders 2022-05-27 14:52:00 -04:00
David Sidrane 39e53711d5
flash_cache:Flush complete cache line 2022-05-27 14:44:54 -04:00
David Sidrane 1294851bb6
boards: STM32H7 pad to 256 bit - 32 bytes (#19724) 2022-05-27 14:44:51 -04:00
David Sidrane 1c15a1a7f4
px4_fmu-v6c:Fix mag rotation 2022-05-27 14:43:47 -04:00
David Sidrane 21567ca187
boards: new px4_fmu-v6c board support (#19544) 2022-05-27 14:42:55 -04:00
bresch 8e789bcc7f
ekf2_post-processing: use estimator_status_flags instead of bitmasks 2022-05-24 10:30:52 -04:00
Julian Oes d699d5f27e
sitl_gazebo: update submodule
This fixes the issue where HITL doesn't connect over USB.
2022-05-24 09:43:05 -04:00
Julian Oes 4ae97c505f
commander: lockdown is not termination
We use lockdown to prevent outputs like motors and servos from being
active in HITL simulation. This means that we can't treat the lockdown
flag as a flight_terminated, otherwise we can't arm in HITL at all.
2022-05-24 09:42:38 -04:00
Daniel Agar b8ce2a6039
icm42688p: only check configured registers periodically (as intended) 2022-05-23 14:58:37 -04:00
bresch 1f399e5b33
ekf2: use explicit flags instead of bitmask position
This prevents bitmask mismatch when a new flag is inserted
2022-05-23 14:57:17 -04:00
Serhat Aksun d67cddae7d
sensors/vehicle_magnetometer: fix multi_mode check
Signed-off-by: Serhat Aksun <serhat.aksun@maxwell-innovations.com>
2022-05-23 10:10:22 -04:00
Julian Oes 0290282b17
ROMFS: disable UAVCAN in HITL
Without this, uavcan creates MixingOutput classes which then create
empty actuator_outputs publications. This then prevents the motor
output in HITL to be forwarded to the simulator via mavlink.
2022-05-22 10:27:07 -04:00
Nicolas MARTIN 39d1c79f48
HITL: undefined time_remaining_s should be NAN 2022-05-20 09:40:28 -04:00
Nico van Duijn ad410a2512
Commander: ignore MAV_CMD_REQUEST_MSG
This commit adds the MAV_CMD_REQUEST_MESSAGE to the list of vehicle
commands which are ignored without generating a warning sound.
2022-05-20 09:40:22 -04:00
Daniel Agar 453acdce31
.vscode/.gitignore ignore all log files 2022-05-20 09:40:07 -04:00
Beat Küng afb2538da3
output drivers: init SmartLock after exit_and_cleanup
This fixes an invalid memory access when exiting the module:
exit_and_cleanup destroys the object, but lock_guard is destructed after
and accesses the lock.
2022-05-12 08:17:15 -04:00
alexklimaj af58c412c3
Fix uavcan battery causing immediate RTL time remaining low 2022-05-11 21:49:13 -04:00
Daniel Agar d5226b28ce
drivers/rc_input: ensure RC inversion is disabled initially and latch RC_INPUT_PROTO conservatively
- this allows jumping straight to a non-SBUS RC protocol
 - increased the scan time per protocol 300->500 ms, which the newer DSM parser seems to need in some cases.
 - only set RC_INPUT_PROTO if we've had a successful RC lock for > 3 seconds
2022-05-11 14:31:51 -04:00
Beat Küng b091ea9fd9
log_writer_file: fix corner case when mission log is enabled
Normally _should_run for mission is only ever true if _should_run for the
normal log is. There are exceptions though:
- the log buffer fails to allocate
- there was a write failure (e.g. due to SD card removal)
In that situation, the writer would not wait anymore but busy-loop.
2022-05-11 10:07:46 -04:00
Beat Küng 9e91ca8294
log_writer_file: protect access to _should_run, use px4::atomicbool for _exit_thread 2022-05-11 10:07:46 -04:00
Igor Mišić 8302f076e7
uavcan: use timer 6 by default on stm32f7 2022-05-10 12:43:26 -04:00
Thomas Stastny de26ffa6e0 fw pos ctrl: turn back to takeoff point with npfg 2022-05-06 13:08:07 -04:00
Thomas Stastny f60d38db65 fw pos ctrl: add missing guidance control interval setting to control_manual_position() 2022-05-06 13:08:07 -04:00
Thomas Stastny 5e3c8d2fa0 fw pos ctrl: fix state switching logic for takeoff and landing 2022-05-06 13:08:07 -04:00
Matthias Grob 90998837ec
Commander: ensure diconnected battery is cleared from bit field 2022-05-06 10:46:40 -04:00
Beat Küng 8cff9a1e04
commander: fix incorrect return in set_link_loss_nav_state()
If both local position and altitude were not valid, then both RC loss and
datalink loss would not trigger any failsafe at all, independently from
the configured action.
2022-05-06 10:15:30 -04:00
bresch f8ff34f82d
ekf2: optimize KHP computation
Calculating K(HP) takes less operations than (KH)P because K and H are
vectors.

Without considering the sparsity optimization:
- KH (24*24 operations) is then a 24x24 matrix an it takes
24^3 operations to multiply it with P. Total: 14400 op

- HP (24*(24+24-1) operations) is a row vector
and it takes 24 operations to left-multiply it by K. Total:1152 op
2022-05-06 10:15:26 -04:00
Beat Küng e69d9ec48f
dshot: avoid using pwm failsafe params when dynamic mixing is enabled 2022-05-02 11:43:51 +02:00
Beat Küng f033e164fe
fix dshot: remove setAllFailsafeValues
Fixes a regression from c1e5e666f0,
where with static mixers the dshot outputs would go to max instead of 0
in a failsafe case.
2022-04-28 13:29:40 -04:00
Daniel Agar 41191765ad
drivers/rc_input: RC_INPUT_PROTO parameter minimal implementation (#19539)
Co-authored-by: chris1seto <chris12892@gmail.com>

Co-authored-by: chris1seto <chris12892@gmail.com>
2022-04-28 13:27:15 -04:00
308 changed files with 11841 additions and 1840 deletions

View File

@ -102,6 +102,7 @@ pipeline {
"px4_fmu-v5_uavcanv0periph",
"px4_fmu-v5_uavcanv1",
"px4_fmu-v5x_default",
"px4_fmu-v6c_default",
"px4_fmu-v6u_default",
"px4_fmu-v6x_default",
"px4_io-v2_default",

View File

@ -21,6 +21,7 @@ jobs:
ark_can-gps,
ark_can-rtk-gps,
ark_cannode,
ark_fmu-v6x,
atl_mantis-edu,
av_x-v1,
bitcraze_crazyflie,
@ -60,6 +61,7 @@ jobs:
px4_fmu-v4pro,
px4_fmu-v5,
px4_fmu-v5x,
px4_fmu-v6c,
px4_fmu-v6u,
px4_fmu-v6x,
sky-drones_smartap-airlink,

2
.vscode/.gitignore vendored
View File

@ -9,3 +9,5 @@ launch.json
ipch/
browse.vc.db*
*.log

View File

@ -131,6 +131,16 @@ CONFIG:
buildType: MinSizeRel
settings:
CONFIG: ark_cannode_canbootloader
ark_fmu-v6x_bootloader:
short: ark_fmu-v6x_bootloader
buildType: MinSizeRel
settings:
CONFIG: ark_fmu-v6x_bootloader
ark_fmu-v6x_default:
short: ark_fmu-v6x_default
buildType: MinSizeRel
settings:
CONFIG: ark_fmu-v6x_default
atl_mantis-edu_default:
short: atl_mantis-edu
buildType: MinSizeRel

View File

@ -37,8 +37,8 @@ menu "Toolchain"
help
forces nolockstep behaviour, despite REPLAY env variable
config BOARD_LINUX
bool "Linux OS"
config BOARD_LINUX_TARGET
bool "Linux OS Target"
depends on PLATFORM_POSIX
help
Board Platform is running the Linux operating system

View File

@ -325,12 +325,13 @@ px4io_update: px4_io-v2_default cubepilot_io-v2_default
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v5/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v5x/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v6x/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v6c/extras/px4_io-v2_default.bin
# cubepilot_io-v2_default
cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeorange/extras/cubepilot_io-v2_default.bin
cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin
git status
bootloaders_update: cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader
bootloaders_update: cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader holybro_kakuteh7_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-classic_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6c_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader
git status
.PHONY: coverity_scan

View File

@ -61,6 +61,8 @@ param set-default HIL_ACT_FUNC6 400
param set SYS_HITL 1
param set UAVCAN_ENABLE 0
# disable some checks to allow to fly
# - with usb
param set-default CBRK_USB_CHK 197848

View File

@ -15,6 +15,8 @@ set MIXER quad_x
param set SYS_HITL 1
param set UAVCAN_ENABLE 0
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.15
param set-default CA_ROTOR0_PY 0.15

View File

@ -94,6 +94,8 @@ param set-default HIL_ACT_FUNC8 203
param set SYS_HITL 1
param set UAVCAN_ENABLE 0
# disable some checks to allow to fly
# - with usb
param set-default CBRK_USB_CHK 197848

View File

@ -1,6 +1,6 @@
#!/bin/sh
#
# @name PX4 Vision DevKit Platform
# @name PX4 Vision Dev Kit v1
#
# @type Quadrotor x
# @class Copter

View File

@ -0,0 +1,134 @@
#!/bin/sh
#
# @name PX4 Vision Dev Kit v1.5
#
# @type Quadrotor x
# @class Copter
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.mc_defaults
# System parameters
# use FMU motor outputs for less delay in the rate control loop
param set-default SYS_USE_IO 0
# Commander Parameters
param set-default COM_OBS_AVOID 1
param set-default COM_DISARM_LAND 0.5
# EKF2 parameters
param set-default EKF2_AID_MASK 35
param set-default EKF2_IMU_POS_X 0.02
param set-default EKF2_GPS_POS_X 0.055
param set-default EKF2_GPS_POS_Z -0.15
param set-default EKF2_MIN_RNG 0.03
param set-default EKF2_OF_POS_X 0.055
param set-default EKF2_OF_POS_Y 0.02
param set-default EKF2_OF_POS_Z 0.065
param set-default EKF2_REQ_HDRIFT 0.3
param set-default EKF2_REQ_SACC 1
param set-default EKF2_REQ_VDRIFT 0.3
param set-default EKF2_RNG_A_HMAX 8
param set-default EKF2_RNG_A_VMAX 2
param set-default EKF2_RNG_POS_X 0.055
param set-default EKF2_RNG_POS_Y -0.01
param set-default EKF2_RNG_POS_Z 0.065
param set-default EKF2_PCOEF_XP -0.25
param set-default EKF2_PCOEF_YN -0.55
param set-default EKF2_PCOEF_YP -0.55
# MAVLink parameters
param set-default MAV_0_CONFIG 101
param set-default MAV_1_CONFIG 102
param set-default MAV_1_RATE 80000
param set-default MAV_1_MODE 9
param set-default SER_TEL1_BAUD 921600
# Vehicle attitude PID tuning
param set-default MC_ACRO_EXPO 0
param set-default MC_ACRO_EXPO_Y 0
param set-default MC_ACRO_P_MAX 200
param set-default MC_ACRO_R_MAX 200
param set-default MC_ACRO_SUPEXPO 0
param set-default MC_ACRO_SUPEXPOY 0
param set-default MC_ACRO_Y_MAX 150
param set-default MC_PITCHRATE_D 0.0015
param set-default MC_ROLLRATE_D 0.0015
param set-default MC_YAWRATE_P 0.3
# Position Control Tuning
param set-default CP_DIST 6
param set-default MPC_ACC_DOWN_MAX 5
param set-default MPC_ACC_HOR_MAX 10
param set-default MPC_ACC_UP_MAX 4
param set-default MPC_MANTHR_MIN 0
param set-default MPC_MAN_Y_MAX 120
param set-default MPC_TILTMAX_AIR 45
param set-default MPC_THR_HOVER 0.3
param set-default MPC_TKO_SPEED 1
param set-default MPC_VEL_MANUAL 5
param set-default MPC_XY_CRUISE 5
param set-default MPC_XY_VEL_MAX 5
param set-default MPC_XY_VEL_P_ACC 1.58
param set-default MPC_XY_TRAJ_P 0.3
param set-default MPC_Z_TRAJ_P 0.3
param set-default MPC_Z_VEL_P_ACC 5
param set-default MPC_Z_VEL_I_ACC 3
param set-default MPC_LAND_ALT1 3
param set-default MPC_LAND_ALT2 1
param set-default MPC_POS_MODE 3
param set-default CP_GO_NO_DATA 1
# Navigator Parameters
param set-default NAV_ACC_RAD 2
# use oneshot motor output protocol
param set-default PWM_MAIN_RATE 0
# RTL Parameters
param set-default RTL_DESCEND_ALT 5
param set-default RTL_RETURN_ALT 5
# Logging Parameters
param set-default SDLOG_PROFILE 131
# Sensors Parameters
param set-default SENS_CM8JL65_CFG 202
param set-default SENS_FLOW_MAXHGT 25
param set-default SENS_FLOW_MINHGT 0.5
param set-default IMU_GYRO_CUTOFF 100
param set-default SENS_TFLOW_CFG 103
# Power Parameters
param set-default BAT1_N_CELLS 4
param set-default BAT1_A_PER_V 36.364
param set-default BAT1_V_DIV 18.182
# Circuit breakers
param set-default CBRK_IO_SAFETY 22027
param set-default THR_MDL_FAC 0.3
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.15
param set-default CA_ROTOR0_PY 0.15
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -0.15
param set-default CA_ROTOR1_PY -0.15
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.15
param set-default CA_ROTOR2_PY -0.15
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.15
param set-default CA_ROTOR3_PY 0.15
param set-default CA_ROTOR3_KM -0.05
# Outputs
param set-default PWM_AUX_FUNC1 101
param set-default PWM_AUX_FUNC2 102
param set-default PWM_AUX_FUNC3 103
param set-default PWM_AUX_FUNC4 104

View File

@ -73,6 +73,7 @@ px4_add_romfs_files(
4016_holybro_px4vision
4017_nxp_hovergames
4019_x500_v2
4020_holybro_px4vision_v1_5
4030_3dr_solo
4031_3dr_quad
4040_reaper

View File

@ -17,17 +17,21 @@ set OUTPUT_DEV none
set OUTPUT_AUX_DEV /dev/pwm_output1
set OUTPUT_EXTRA_DEV /dev/pwm_output0
# set these before starting the modules
# set ESC mask before starting the modules
# setting the numeric parameter to "none" would make the startup script fail
if [ $PWM_AUX_OUT != none ]
then
param set PWM_AUX_OUT ${PWM_AUX_OUT}
else
param set PWM_AUX_OUT 0
fi
if [ $PWM_OUT != none ]
then
param set PWM_MAIN_OUT ${PWM_OUT}
else
param set PWM_AUX_OUT 0
fi
#

View File

@ -171,7 +171,7 @@ else
param select-backup /fs/microsd/parameters_backup.bson
fi
if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X
if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X ARK_FMU_V6X
then
netman update -i eth0
fi
@ -282,28 +282,6 @@ else
param set SYS_AUTOCONFIG 0
fi
#
# Check if UAVCAN is enabled, default to it for ESCs.
#
if param greater -s UAVCAN_ENABLE 0
then
# Start core UAVCAN module.
if uavcan start
then
if param greater UAVCAN_ENABLE 2
then
set OUTPUT_MODE uavcan_esc
fi
else
tune_control play error
fi
else
if param greater -s UAVCAN_V1_ENABLE 0
then
uavcan_v1 start
fi
fi
#
# Check if PX4IO present and update firmware if needed.
# Assumption IOFW set to firmware file and IO_PRESENT = no
@ -556,6 +534,28 @@ else
fi
unset BOARD_BOOTLOADER_UPGRADE
#
# Check if UAVCAN is enabled, default to it for ESCs.
#
if param greater -s UAVCAN_ENABLE 0
then
# Start core UAVCAN module.
if uavcan start
then
if param greater UAVCAN_ENABLE 2
then
set OUTPUT_MODE uavcan_esc
fi
else
tune_control play error
fi
else
if param greater -s UAVCAN_V1_ENABLE 0
then
uavcan_v1 start
fi
fi
#
# End of autostart.
#

View File

@ -11,7 +11,7 @@ from pyulog import ULog
from analysis.detectors import InAirDetector, PreconditionError
from analysis.metrics import calculate_ecl_ekf_metrics
from analysis.checks import perform_ecl_ekf_checks
from analysis.post_processing import get_estimator_check_flags
from analysis.post_processing import get_gps_check_fail_flags
def analyse_ekf(
ulog: ULog, check_levels: Dict[str, float], multi_instance: int = 0,
@ -40,6 +40,11 @@ def analyse_ekf(
except:
raise PreconditionError('could not find estimator_status instance', multi_instance)
try:
estimator_status_flags = ulog.get_dataset('estimator_status_flags', multi_instance).data
except:
raise PreconditionError('could not find estimator_status_flags instance', multi_instance)
try:
_ = ulog.get_dataset('estimator_innovations', multi_instance).data
except:
@ -61,14 +66,14 @@ def analyse_ekf(
'in_air_transition_time': round(in_air.take_off + in_air.log_start, 2),
'on_ground_transition_time': round(in_air.landing + in_air.log_start, 2)}
control_mode, innov_flags, gps_fail_flags = get_estimator_check_flags(estimator_status)
gps_fail_flags = get_gps_check_fail_flags(estimator_status)
sensor_checks, innov_fail_checks = find_checks_that_apply(
control_mode, estimator_status,
estimator_status_flags, estimator_status,
pos_checks_when_sensors_not_fused=pos_checks_when_sensors_not_fused)
metrics = calculate_ecl_ekf_metrics(
ulog, innov_flags, innov_fail_checks, sensor_checks, in_air, in_air_no_ground_effects,
ulog, estimator_status_flags, innov_fail_checks, sensor_checks, in_air, in_air_no_ground_effects,
multi_instance, red_thresh=red_thresh, amb_thresh=amb_thresh)
check_status, master_status = perform_ecl_ekf_checks(
@ -78,12 +83,12 @@ def analyse_ekf(
def find_checks_that_apply(
control_mode: dict, estimator_status: dict, pos_checks_when_sensors_not_fused: bool = False) ->\
estimator_status_flags: dict, estimator_status: dict, pos_checks_when_sensors_not_fused: bool = False) ->\
Tuple[List[str], List[str]]:
"""
finds the checks that apply and stores them in lists for the std checks and the innovation
fail checks.
:param control_mode:
:param estimator_status_flags:
:param estimator_status:
:param b_pos_only_when_sensors_fused:
:return: a tuple of two lists that contain strings for the std checks and for the innovation
@ -97,7 +102,7 @@ def find_checks_that_apply(
innov_fail_checks.append('posv')
# Magnetometer Sensor Checks
if (np.amax(control_mode['yaw_aligned']) > 0.5):
if (np.amax(estimator_status_flags['cs_yaw_align']) > 0.5):
sensor_checks.append('mag')
innov_fail_checks.append('magx')
@ -106,13 +111,14 @@ def find_checks_that_apply(
innov_fail_checks.append('yaw')
# Velocity Sensor Checks
if (np.amax(control_mode['using_gps']) > 0.5):
if (np.amax(estimator_status_flags['cs_gps']) > 0.5):
sensor_checks.append('vel')
innov_fail_checks.append('vel')
innov_fail_checks.append('velh')
innov_fail_checks.append('velv')
# Position Sensor Checks
if (pos_checks_when_sensors_not_fused or (np.amax(control_mode['using_gps']) > 0.5)
or (np.amax(control_mode['using_evpos']) > 0.5)):
if (pos_checks_when_sensors_not_fused or (np.amax(estimator_status_flags['cs_gps']) > 0.5)
or (np.amax(estimator_status_flags['cs_ev_pos']) > 0.5)):
sensor_checks.append('pos')
innov_fail_checks.append('posh')
@ -128,7 +134,7 @@ def find_checks_that_apply(
innov_fail_checks.append('hagl')
# optical flow sensor checks
if (np.amax(control_mode['using_optflow']) > 0.5):
if (np.amax(estimator_status_flags['cs_opt_flow']) > 0.5):
innov_fail_checks.append('ofx')
innov_fail_checks.append('ofy')

View File

@ -123,7 +123,8 @@ def perform_sensor_innov_checks(
('magy', 'magy_fail_percentage', 'mag'),
('magz', 'magz_fail_percentage', 'mag'),
('yaw', 'yaw_fail_percentage', 'yaw'),
('vel', 'vel_fail_percentage', 'vel'),
('velh', 'vel_fail_percentage', 'vel'),
('velv', 'vel_fail_percentage', 'vel'),
('posh', 'pos_fail_percentage', 'pos'),
('tas', 'tas_fail_percentage', 'tas'),
('hagl', 'hagl_fail_percentage', 'hagl'),

View File

@ -11,7 +11,7 @@ import numpy as np
from analysis.detectors import InAirDetector
def calculate_ecl_ekf_metrics(
ulog: ULog, innov_flags: Dict[str, float], innov_fail_checks: List[str],
ulog: ULog, estimator_status_flags: Dict[str, float], innov_fail_checks: List[str],
sensor_checks: List[str], in_air: InAirDetector, in_air_no_ground_effects: InAirDetector,
multi_instance: int = 0, red_thresh: float = 1.0, amb_thresh: float = 0.5) -> Tuple[dict, dict, dict, dict]:
@ -20,7 +20,7 @@ def calculate_ecl_ekf_metrics(
red_thresh=red_thresh, amb_thresh=amb_thresh)
innov_fail_metrics = calculate_innov_fail_metrics(
innov_flags, innov_fail_checks, in_air, in_air_no_ground_effects)
estimator_status_flags, innov_fail_checks, in_air, in_air_no_ground_effects)
imu_metrics = calculate_imu_metrics(ulog, multi_instance, in_air_no_ground_effects)
@ -90,10 +90,10 @@ def calculate_sensor_metrics(
def calculate_innov_fail_metrics(
innov_flags: dict, innov_fail_checks: List[str], in_air: InAirDetector,
estimator_status_flags: dict, innov_fail_checks: List[str], in_air: InAirDetector,
in_air_no_ground_effects: InAirDetector) -> dict:
"""
:param innov_flags:
:param estimator_status_flags:
:param innov_fail_checks:
:param in_air:
:param in_air_no_ground_effects:
@ -103,17 +103,18 @@ def calculate_innov_fail_metrics(
innov_fail_metrics = dict()
# calculate innovation check fail metrics
for signal_id, signal, result in [('posv', 'posv_innov_fail', 'hgt_fail_percentage'),
('magx', 'magx_innov_fail', 'magx_fail_percentage'),
('magy', 'magy_innov_fail', 'magy_fail_percentage'),
('magz', 'magz_innov_fail', 'magz_fail_percentage'),
('yaw', 'yaw_innov_fail', 'yaw_fail_percentage'),
('vel', 'vel_innov_fail', 'vel_fail_percentage'),
('posh', 'posh_innov_fail', 'pos_fail_percentage'),
('tas', 'tas_innov_fail', 'tas_fail_percentage'),
('hagl', 'hagl_innov_fail', 'hagl_fail_percentage'),
('ofx', 'ofx_innov_fail', 'ofx_fail_percentage'),
('ofy', 'ofy_innov_fail', 'ofy_fail_percentage')]:
for signal_id, signal, result in [('posv', 'reject_ver_pos', 'hgt_fail_percentage'),
('magx', 'reject_mag_x', 'magx_fail_percentage'),
('magy', 'reject_mag_y', 'magy_fail_percentage'),
('magz', 'reject_mag_z', 'magz_fail_percentage'),
('yaw', 'reject_yaw', 'yaw_fail_percentage'),
('velh', 'reject_hor_vel', 'vel_fail_percentage'),
('velv', 'reject_ver_vel', 'vel_fail_percentage'),
('posh', 'reject_hor_pos', 'pos_fail_percentage'),
('tas', 'reject_airspeed', 'tas_fail_percentage'),
('hagl', 'reject_hagl', 'hagl_fail_percentage'),
('ofx', 'reject_optflow_x', 'ofx_fail_percentage'),
('ofy', 'reject_optflow_y', 'ofy_fail_percentage')]:
# only run innov fail checks, if they apply.
if signal_id in innov_fail_checks:
@ -125,7 +126,7 @@ def calculate_innov_fail_metrics(
in_air_detector = in_air
innov_fail_metrics[result] = calculate_stat_from_signal(
innov_flags, 'estimator_status', signal, in_air_detector,
estimator_status_flags, 'estimator_status_flags', signal, in_air_detector,
lambda x: 100.0 * np.mean(x > 0.5))
return innov_fail_metrics
@ -152,7 +153,7 @@ def calculate_imu_metrics(ulog: ULog, multi_instance, in_air_no_ground_effects:
if vehicle_imu_status_data['accel_device_id'][0] == estimator_status_data['accel_device_id'][0]:
for signal, result in [('delta_angle_coning_metric', 'imu_coning'),
for signal, result in [('gyro_coning_vibration', 'imu_coning'),
('gyro_vibration_metric', 'imu_hfgyro'),
('accel_vibration_metric', 'imu_hfaccel')]:

View File

@ -7,115 +7,6 @@ from typing import Tuple
import numpy as np
def get_estimator_check_flags(estimator_status: dict) -> Tuple[dict, dict, dict]:
"""
:param estimator_status:
:return:
"""
control_mode = get_control_mode_flags(estimator_status)
innov_flags = get_innovation_check_flags(estimator_status)
gps_fail_flags = get_gps_check_fail_flags(estimator_status)
return control_mode, innov_flags, gps_fail_flags
def get_control_mode_flags(estimator_status: dict) -> dict:
"""
:param estimator_status:
:return:
"""
control_mode = dict()
# extract control mode metadata from estimator_status.control_mode_flags
# 0 - true if the filter tilt alignment is complete
# 1 - true if the filter yaw alignment is complete
# 2 - true if GPS measurements are being fused
# 3 - true if optical flow measurements are being fused
# 4 - true if a simple magnetic yaw heading is being fused
# 5 - true if 3-axis magnetometer measurement are being fused
# 6 - true if synthetic magnetic declination measurements are being fused
# 7 - true when the vehicle is airborne
# 8 - true when wind velocity is being estimated
# 9 - true when baro height is being fused as a primary height reference
# 10 - true when range finder height is being fused as a primary height reference
# 11 - true when range finder height is being fused as a primary height reference
# 12 - true when local position data from external vision is being fused
# 13 - true when yaw data from external vision measurements is being fused
# 14 - true when height data from external vision measurements is being fused
# 15 - true when synthetic sideslip measurements are being fused
# 16 - true true when the mag field does not match the expected strength
# 17 - true true when the vehicle is operating as a fixed wing vehicle
# 18 - true when the magnetometer has been declared faulty and is no longer being used
# 19 - true true when airspeed measurements are being fused
# 20 - true true when protection from ground effect induced static pressure rise is active
# 21 - true when rng data wasn't ready for more than 10s and new rng values haven't changed enough
# 22 - true when yaw (not ground course) data from a GPS receiver is being fused
# 23 - true when the in-flight mag field alignment has been completed
# 24 - true when local earth frame velocity data from external vision measurements are being fused
# 25 - true when we are using a synthesized measurement for the magnetometer Z component
control_mode['tilt_aligned'] = ((2 ** 0 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['yaw_aligned'] = ((2 ** 1 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_gps'] = ((2 ** 2 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_optflow'] = ((2 ** 3 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_magyaw'] = ((2 ** 4 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_mag3d'] = ((2 ** 5 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_magdecl'] = ((2 ** 6 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['airborne'] = ((2 ** 7 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['estimating_wind'] = ((2 ** 8 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_barohgt'] = ((2 ** 9 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_rnghgt'] = ((2 ** 10 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_gpshgt'] = ((2 ** 11 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_evpos'] = ((2 ** 12 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_evyaw'] = ((2 ** 13 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_evhgt'] = ((2 ** 14 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['fuse_beta'] = ((2 ** 15 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['mag_field_disturbed'] = ((2 ** 16 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['fixed_wing'] = ((2 ** 17 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['mag_fault'] = ((2 ** 18 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['fuse_aspd'] = ((2 ** 19 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['gnd_effect'] = ((2 ** 20 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['rng_stuck'] = ((2 ** 21 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['gps_yaw'] = ((2 ** 22 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['mag_aligned_in_flight'] = ((2 ** 23 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['ev_vel'] = ((2 ** 24 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['synthetic_mag_z'] = ((2 ** 25 & estimator_status['control_mode_flags']) > 0) * 1
return control_mode
def get_innovation_check_flags(estimator_status: dict) -> dict:
"""
:param estimator_status:
:return:
"""
innov_flags = dict()
# innovation_check_flags summary
# 0 - true if velocity observations have been rejected
# 1 - true if horizontal position observations have been rejected
# 2 - true if true if vertical position observations have been rejected
# 3 - true if the X magnetometer observation has been rejected
# 4 - true if the Y magnetometer observation has been rejected
# 5 - true if the Z magnetometer observation has been rejected
# 6 - true if the yaw observation has been rejected
# 7 - true if the airspeed observation has been rejected
# 8 - true if synthetic sideslip observation has been rejected
# 9 - true if the height above ground observation has been rejected
# 10 - true if the X optical flow observation has been rejected
# 11 - true if the Y optical flow observation has been rejected
innov_flags['vel_innov_fail'] = ((2 ** 0 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['posh_innov_fail'] = ((2 ** 1 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['posv_innov_fail'] = ((2 ** 2 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['magx_innov_fail'] = ((2 ** 3 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['magy_innov_fail'] = ((2 ** 4 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['magz_innov_fail'] = ((2 ** 5 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['yaw_innov_fail'] = ((2 ** 6 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['tas_innov_fail'] = ((2 ** 7 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['sli_innov_fail'] = ((2 ** 8 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['hagl_innov_fail'] = ((2 ** 9 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['ofx_innov_fail'] = ((2 ** 10 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['ofy_innov_fail'] = ((2 ** 11 & estimator_status['innovation_check_flags']) > 0) * 1
return innov_flags
def get_gps_check_fail_flags(estimator_status: dict) -> dict:
"""
:param estimator_status:

View File

@ -11,7 +11,7 @@ import numpy as np
from matplotlib.backends.backend_pdf import PdfPages
from pyulog import ULog
from analysis.post_processing import magnetic_field_estimates_from_states, get_estimator_check_flags
from analysis.post_processing import magnetic_field_estimates_from_states, get_gps_check_fail_flags
from plotting.data_plots import TimeSeriesPlot, InnovationPlot, ControlModeSummaryPlot, \
CheckFlagsPlot
from analysis.detectors import PreconditionError
@ -33,6 +33,11 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
except:
raise PreconditionError('could not find estimator_status instance', multi_instance)
try:
estimator_status_flags = ulog.get_dataset('estimator_status_flags', multi_instance).data
except:
raise PreconditionError('could not find estimator_status_flags instance', multi_instance)
try:
estimator_states = ulog.get_dataset('estimator_states', multi_instance).data
except:
@ -68,12 +73,13 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
except:
raise PreconditionError('could not find innovation data')
control_mode, innov_flags, gps_fail_flags = get_estimator_check_flags(estimator_status)
gps_fail_flags = get_gps_check_fail_flags(estimator_status)
status_time = 1e-6 * estimator_status['timestamp']
status_flags_time = 1e-6 * estimator_status_flags['timestamp']
b_finishes_in_air, b_starts_in_air, in_air_duration, in_air_transition_time, \
on_ground_transition_time = detect_airtime(control_mode, status_time)
on_ground_transition_time = detect_airtime(estimator_status_flags, status_flags_time)
with PdfPages(output_plot_filename) as pdf_pages:
@ -173,9 +179,9 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
# plot control mode summary A
data_plot = ControlModeSummaryPlot(
status_time, control_mode, [['tilt_aligned', 'yaw_aligned'],
['using_gps', 'using_optflow', 'using_evpos'], ['using_barohgt', 'using_gpshgt',
'using_rnghgt', 'using_evhgt'], ['using_magyaw', 'using_mag3d', 'using_magdecl']],
status_flags_time, estimator_status_flags, [['cs_tilt_align', 'cs_yaw_align'],
['cs_gps', 'cs_opt_flow', 'cs_ev_pos'], ['cs_baro_hgt', 'cs_gps_hgt',
'cs_rng_hgt', 'cs_ev_hgt'], ['cs_mag_hdg', 'cs_mag_3d', 'cs_mag_dec']],
x_label='time (sec)', y_labels=['aligned', 'pos aiding', 'hgt aiding', 'mag aiding'],
annotation_text=[['tilt alignment', 'yaw alignment'], ['GPS aiding', 'optical flow aiding',
'external vision aiding'], ['Baro aiding', 'GPS aiding', 'rangefinder aiding',
@ -188,7 +194,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
# plot control mode summary B
# construct additional annotations for the airborne plot
airborne_annotations = list()
if np.amin(np.diff(control_mode['airborne'])) > -0.5:
if np.amin(np.diff(estimator_status_flags['cs_in_air'])) > -0.5:
airborne_annotations.append(
(on_ground_transition_time, 'air to ground transition not detected'))
else:
@ -197,7 +203,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
if in_air_duration > 0.0:
airborne_annotations.append(((in_air_transition_time + on_ground_transition_time) / 2,
'duration = {:.1f} sec'.format(in_air_duration)))
if np.amax(np.diff(control_mode['airborne'])) < 0.5:
if np.amax(np.diff(estimator_status_flags['cs_in_air'])) < 0.5:
airborne_annotations.append(
(in_air_transition_time, 'ground to air transition not detected'))
else:
@ -205,7 +211,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
(in_air_transition_time, 'in-air at {:.1f} sec'.format(in_air_transition_time)))
data_plot = ControlModeSummaryPlot(
status_time, control_mode, [['airborne'], ['estimating_wind']],
status_flags_time, estimator_status_flags, [['cs_in_air'], ['cs_wind']],
x_label='time (sec)', y_labels=['airborne', 'estimating wind'], annotation_text=[[], []],
additional_annotation=[airborne_annotations, []],
plot_title='EKF Control Status - Figure B', pdf_handle=pdf_pages)
@ -214,15 +220,15 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
# plot innovation_check_flags summary
data_plot = CheckFlagsPlot(
status_time, innov_flags, [['vel_innov_fail', 'posh_innov_fail'], ['posv_innov_fail',
'hagl_innov_fail'],
['magx_innov_fail', 'magy_innov_fail', 'magz_innov_fail',
'yaw_innov_fail'], ['tas_innov_fail'], ['sli_innov_fail'],
['ofx_innov_fail',
'ofy_innov_fail']], x_label='time (sec)',
status_flags_time, estimator_status_flags, [['reject_hor_vel', 'reject_hor_pos'], ['reject_ver_vel', 'reject_ver_pos',
'reject_hagl'],
['reject_mag_x', 'reject_mag_y', 'reject_mag_z',
'reject_yaw'], ['reject_airspeed'], ['reject_sideslip'],
['reject_optflow_x',
'reject_optflow_y']], x_label='time (sec)',
y_labels=['failed', 'failed', 'failed', 'failed', 'failed', 'failed'],
y_lim=(-0.1, 1.1),
legend=[['vel NED', 'pos NE'], ['hgt absolute', 'hgt above ground'],
legend=[['vel NE', 'pos NE'], ['vel D', 'hgt absolute', 'hgt above ground'],
['mag_x', 'mag_y', 'mag_z', 'yaw'], ['airspeed'], ['sideslip'],
['flow X', 'flow Y']],
plot_title='EKF Innovation Test Fails', annotate=False, pdf_handle=pdf_pages)
@ -344,33 +350,33 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
data_plot.close()
def detect_airtime(control_mode, status_time):
def detect_airtime(estimator_status_flags, status_flags_time):
# define flags for starting and finishing in air
b_starts_in_air = False
b_finishes_in_air = False
# calculate in-air transition time
if (np.amin(control_mode['airborne']) < 0.5) and (np.amax(control_mode['airborne']) > 0.5):
in_air_transtion_time_arg = np.argmax(np.diff(control_mode['airborne']))
in_air_transition_time = status_time[in_air_transtion_time_arg]
elif (np.amax(control_mode['airborne']) > 0.5):
in_air_transition_time = np.amin(status_time)
if (np.amin(estimator_status_flags['cs_in_air']) < 0.5) and (np.amax(estimator_status_flags['cs_in_air']) > 0.5):
in_air_transtion_time_arg = np.argmax(np.diff(estimator_status_flags['cs_in_air']))
in_air_transition_time = status_flags_time[in_air_transtion_time_arg]
elif (np.amax(estimator_status_flags['cs_in_air']) > 0.5):
in_air_transition_time = np.amin(status_flags_time)
print('log starts while in-air at ' + str(round(in_air_transition_time, 1)) + ' sec')
b_starts_in_air = True
else:
in_air_transition_time = float('NaN')
print('always on ground')
# calculate on-ground transition time
if (np.amin(np.diff(control_mode['airborne'])) < 0.0):
on_ground_transition_time_arg = np.argmin(np.diff(control_mode['airborne']))
on_ground_transition_time = status_time[on_ground_transition_time_arg]
elif (np.amax(control_mode['airborne']) > 0.5):
on_ground_transition_time = np.amax(status_time)
if (np.amin(np.diff(estimator_status_flags['cs_in_air'])) < 0.0):
on_ground_transition_time_arg = np.argmin(np.diff(estimator_status_flags['cs_in_air']))
on_ground_transition_time = status_flags_time[on_ground_transition_time_arg]
elif (np.amax(estimator_status_flags['cs_in_air']) > 0.5):
on_ground_transition_time = np.amax(status_flags_time)
print('log finishes while in-air at ' + str(round(on_ground_transition_time, 1)) + ' sec')
b_finishes_in_air = True
else:
on_ground_transition_time = float('NaN')
print('always on ground')
if (np.amax(np.diff(control_mode['airborne'])) > 0.5) and (np.amin(np.diff(control_mode['airborne'])) < -0.5):
if (np.amax(np.diff(estimator_status_flags['cs_in_air'])) > 0.5) and (np.amin(np.diff(estimator_status_flags['cs_in_air'])) < -0.5):
if ((on_ground_transition_time - in_air_transition_time) > 0.0):
in_air_duration = on_ground_transition_time - in_air_transition_time
else:

@ -1 +1 @@
Subproject commit 2cf56d0bf8a9119cadc1a44d20d641ab24a6a42d
Subproject commit 48440d7b5c78a21182415266334981f1163f4b2c

View File

@ -130,8 +130,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDIO_BLOCKSETUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@ -174,7 +173,7 @@ CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI2=y
CONFIG_STM32_SPI4=y
CONFIG_STM32_SPI4_DMA=y
CONFIG_STM32_SPI4_DMA_BUFFER=1024
CONFIG_STM32_SPI4_DMA_BUFFER=512
CONFIG_STM32_SPI_DMA=y
CONFIG_STM32_SPI_DMATHRESHOLD=8
CONFIG_STM32_TIM10=y

View File

@ -105,8 +105,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

View File

@ -107,8 +107,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

View File

@ -107,8 +107,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

View File

@ -107,8 +107,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

View File

@ -0,0 +1,3 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROMFSROOT=""

View File

@ -0,0 +1,96 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ETHERNET=y
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_BMP388=y
CONFIG_DRIVERS_BAROMETER_MS5611=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_HEATER=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PWM_OUT_SIM=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2
CONFIG_MODULES_AIRSPEED_SELECTOR=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_L1=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_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_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_DMESG=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_NETMAN=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_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y

Binary file not shown.

Binary file not shown.

View File

@ -0,0 +1,13 @@
{
"board_id": 57,
"magic": "ARKFWv1",
"description": "Firmware for the ARKFMUv6X board",
"image": "",
"build_time": 0,
"summary": "ARKFMUv6X",
"version": "0.1",
"image_size": 0,
"image_maxsize": 1966080,
"git_identity": "",
"board_revision": 0
}

View File

@ -0,0 +1,26 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
# Mavlink ethernet (CFG 1000)
param set-default MAV_2_CONFIG 1000
param set-default MAV_2_BROADCAST 1
param set-default MAV_2_MODE 0
param set-default MAV_2_RADIO_CTL 0
param set-default MAV_2_RATE 100000
param set-default MAV_2_REMOTE_PRT 14550
param set-default MAV_2_UDP_PRT 14550
param set-default SENS_EN_INA238 0
param set-default SENS_EN_INA228 0
param set-default SENS_EN_INA226 1
if ver hwtypecmp ARKV6X001000 ARKV6X001001 ARKV6X001002 ARKV6X001003 ARKV6X001004 ARKV6X001005 ARKV6X001006 ARKV6X001007
then
param set-default SYS_USE_IO 0
else
param set-default SYS_USE_IO 1
fi
safety_button start

View File

@ -0,0 +1,47 @@
#!/bin/sh
#
# PX4 FMUv6X specific board sensors init
#------------------------------------------------------------------------------
board_adc start
if param compare SENS_EN_INA226 1
then
# Start Digital power monitors
ina226 -X -b 1 -t 1 -k start
ina226 -X -b 2 -t 2 -k start
fi
if param compare SENS_EN_INA228 1
then
# Start Digital power monitors
ina228 -X -b 1 -t 1 -k start
ina228 -X -b 2 -t 2 -k start
fi
if param compare SENS_EN_INA238 1
then
# Start Digital power monitors
ina238 -X -b 1 -t 1 -k start
ina238 -X -b 2 -t 2 -k start
fi
# Internal SPI bus IIM42652
iim42652 -R 3 -s -b 1 start
# Internal SPI bus ICM42688p
icm42688p -R 9 -s -b 2 start
# Internal SPI bus ICM42688p
icm42688p -R 6 -s -b 3 start
# Internal magnetometer on I2c
bmm150 -I start
# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer)
ist8310 -X -b 1 -R 10 start
# Possible internal Baro
bmp388 -I start
# Baro on I2C3
ms5611 -X start

View File

@ -0,0 +1,17 @@
#
# 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.

View File

@ -0,0 +1,96 @@
#
# 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/ark/fmu-v6x/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H753II=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL_RESET=y
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=0x0035
CONFIG_CDCACM_PRODUCTSTR="ARK BL FMU v6X.x"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3185
CONFIG_CDCACM_VENDORSTR="ARK"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DISABLE_MQUEUE=y
CONFIG_DISABLE_PTHREAD=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_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_LIB_BOARDCTL=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_SDCLONE_DISABLE=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_DMA2=y
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_UART7=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_UART7_RXBUFSIZE=512
CONFIG_UART7_RXDMA=y
CONFIG_UART7_TXBUFSIZE=512
CONFIG_UART7_TXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="bootloader_main"

View File

@ -0,0 +1,558 @@
/************************************************************************************
* nuttx-configs/px4_fmu-v6x/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_PX4_FMU_V6X_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_PX4_FMU_V6X_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 px4_fmu-v6X 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 2 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 PX4 FMUV6X board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and
* LED_RED a Red 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() */
/* LED definitions ******************************************************************/
/* The px4_fmu-v6x board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and
* LED_RED a Red 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_3 /* PB7 */
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */
#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */
#define GPIO_UART4_TX GPIO_UART4_TX_6 /* PH13 */
#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */
#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */
// GPIO_UART5_RTS No remap /* PC8 */
// GPIO_UART5_CTS No remap /* PC9 */
#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_4 /* PF6 */
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
#define GPIO_UART7_RTS (GPIO_UART7_RTS_2 | GPIO_PULLDOWN) /* PF8 */
#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
/* CAN
*
* CAN1 is routed to transceiver.
* CAN2 is routed to transceiver.
*/
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
/* SPI
* SPI1 is sensors1
* SPI2 is sensors2
* SPI3 is sensors3
* SPI4 is Not Used
* SPI5 is FRAM
* SPI6 is EXTERNAL1
*
*/
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_3 /* PG9 */
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */
#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_2 /* PH7 */
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF11 */
#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */
#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_3) /* PB3 */
/* I2C
*
* The optional _GPIO configurations allow the I2C driver to manually
* reset the bus to clear stuck slaves. They match the pin configuration,
* but are normally-high GPIOs.
*
*/
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
#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_PIN9)
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0)
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 /* PA8 */
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN8)
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8)
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14)
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15)
/* SDMMC2
*
* VDD 3.3
* GND
* SDMMC2_CK PD6
* SDMMC2_CMD PD7
* SDMMC2_D0 PB14
* SDMMC2_D1 PB15
* SDMMC2_D2 PG11
* SDMMC2_D3 PB4
*/
#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_1 /* PD6 */
#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */
// GPIO_SDMMC2_D0 No Remap /* PB14 */
// GPIO_SDMMC2_D1 No Remap /* PB15 */
#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 /* PG11 */
// GPIO_SDMMC2_D3 No Remap /* PB4 */
/* The STM32 H7 connects to a TI DP83848TSQ/NOPB
* using RMII
*
* STM32 H7 BOARD DP83848TSQ/NOPB
* GPIO SIGNAL PIN NAME
* -------- ------------ -------------
* PA7 ETH_CRS_DV CRS_DV
* PC1 ETH_MDC MDC
* PA2 ETH_MDIO MDIO
* PA1 ETH_REF_CL X1
* PC4 ETH_RXD0 RX_D0
* PC5 ETH_RXD1 RX_D1
* PB11 ETH_TX_EN TX_EN
* PG13 ETH_TXD0 TX_D0
* PG12 ETH_TXD1 TX_D1
*
* The PHY address is 1, since COL/PHYAD0 features a pull up.
*/
#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 /* PB11 */
#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2 /* PG13 */
#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_2 /* PG12 */
/* 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_PX4_FMU_V6X_INCLUDE_BOARD_H */

View File

@ -0,0 +1,87 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#pragma once
// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned
// V
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 ICM-20649 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 ICM-20649 */
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */
//#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */
//#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */
//#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 Telem3 */
//#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 Telem3 */
//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */
//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */
//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 EXT2 */
//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 EXT2 */
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */
// Assigned in timer_config.cpp
// Timer 4 /* 7 DMA1:32 TIM4UP */
// Timer 5 /* 8 DMA1:50 TIM5UP */
// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned
// V
#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */
#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */
#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */
#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */
#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */
//#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_1 /* DMA1:81 GPS2 */
//#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_1 /* DMA1:82 GPS2 */
// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned
// V
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */

View File

@ -0,0 +1,295 @@
#
# 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_ARP is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_EXEC 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/ark/fmu-v6x/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H753II=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=0x0035
CONFIG_CDCACM_PRODUCTSTR="ARK FMU v6X.x"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3185
CONFIG_CDCACM_VENDORSTR="ARK"
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_ETH0_PHY_LAN8742A=y
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_FSUTILS_IPCFG=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_THROTTLE=0
CONFIG_IPCFG_BINARY=y
CONFIG_IPCFG_CHARDEV=y
CONFIG_IPCFG_PATH="/fs/mtd_net"
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_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_NET=y
CONFIG_NETDB_DNSCLIENT=y
CONFIG_NETDB_DNSCLIENT_ENTRIES=8
CONFIG_NETDB_DNSSERVER_NOADDR=y
CONFIG_NETDEV_PHY_IOCTL=y
CONFIG_NETINIT_DHCPC=y
CONFIG_NETINIT_DNS=y
CONFIG_NETINIT_DNSIPADDR=0XC0A800FE
CONFIG_NETINIT_DRIPADDR=0XC0A800FE
CONFIG_NETINIT_THREAD=y
CONFIG_NETINIT_THREAD_PRIORITY=49
CONFIG_NETUTILS_TELNETD=y
CONFIG_NET_ARP_IPIN=y
CONFIG_NET_ARP_SEND=y
CONFIG_NET_BROADCAST=y
CONFIG_NET_ETH_PKTSIZE=1518
CONFIG_NET_ICMP=y
CONFIG_NET_ICMP_SOCKET=y
CONFIG_NET_SOLINGER=y
CONFIG_NET_TCP=y
CONFIG_NET_TCPBACKLOG=y
CONFIG_NET_TCP_DELAYED_ACK=y
CONFIG_NET_TCP_WRITE_BUFFERS=y
CONFIG_NET_UDP=y
CONFIG_NET_UDP_CHECKSUMS=y
CONFIG_NET_UDP_WRITE_BUFFERS=y
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_TELNET=y
CONFIG_NSH_TELNET_LOGIN=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_ETHMAC=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_PHYSR=31
CONFIG_STM32H7_PHYSR_100MBPS=0x8
CONFIG_STM32H7_PHYSR_FULLDUPLEX=0x10
CONFIG_STM32H7_PHYSR_MODE=0x10
CONFIG_STM32H7_PHYSR_SPEED=0x8
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_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_TIM4=y
CONFIG_STM32H7_TIM5=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART5=y
CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=y
CONFIG_STM32H7_USART1=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_USART6=y
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_DHCPC_RENEW=y
CONFIG_SYSTEM_NSH=y
CONFIG_SYSTEM_PING=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART5_IFLOWCONTROL=y
CONFIG_UART5_OFLOWCONTROL=y
CONFIG_UART5_RXDMA=y
CONFIG_UART5_TXBUFSIZE=3000
CONFIG_UART5_TXDMA=y
CONFIG_UART7_BAUD=57600
CONFIG_UART7_IFLOWCONTROL=y
CONFIG_UART7_OFLOWCONTROL=y
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_RXDMA=y
CONFIG_UART7_TXBUFSIZE=3000
CONFIG_UART7_TXDMA=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_RXDMA=y
CONFIG_USART3_SERIAL_CONSOLE=y
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_USART3_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=1500
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

View File

@ -0,0 +1,215 @@
/****************************************************************************
* 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 PX4 FMUV6X uses an STM32H753II 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 PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by
* default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test
* point is pulled to 3.3V.then the boot will be from 0x1FF0:0000
*
* The STM32H743II 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.
*
* The bootloader uses the first sector of the flash, which is 128K in length.
*/
MEMORY
{
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K
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) }
}

View File

@ -0,0 +1,229 @@
/****************************************************************************
* 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 PX4 FMUV6X uses an STM32H753II 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 PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by
* default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test
* point is pulled to 3.3V.then the boot will be from 0x1FF0:0000
*
* The STM32H743II 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)
EXTERN(board_get_manifest)
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) }
}

View File

@ -0,0 +1,70 @@
############################################################################
#
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# 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 # sdio
nuttx_drivers # sdio
bootloader
)
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common)
else()
add_library(drivers_board
can.c
i2c.cpp
init.c
led.c
mtd.cpp
manifest.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_spi
arch_board_hw_info
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio
px4_layer
)
endif()

View File

@ -0,0 +1,524 @@
/****************************************************************************
*
* Copyright (c) 2016, 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 board_config.h
*
* PX4FMU-v6x 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
****************************************************************************************************/
#undef TRACE_PINS
/* PX4IO connection configuration */
#define BOARD_USES_PX4IO_VERSION 2
#define PX4IO_SERIAL_DEVICE "/dev/ttyS5"
#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
#define PX4IO_SERIAL_BASE STM32_USART6_BASE
#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX
#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR
#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN
#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
/* Configuration ************************************************************************************/
#define BOARD_HAS_LTC44XX_VALIDS 2 // N Bricks
#define BOARD_HAS_USB_VALID 1 // LTC Has USB valid
#define BOARD_HAS_NBAT_V 2d // 2 Digital Voltage
#define BOARD_HAS_NBAT_I 2d // 2 Digital Current
/* PX4FMU GPIOs ***********************************************************************************/
/* Trace Clock and D0-D3 are available on the trace connector
*
* TRACECLK PE2 - Dedicated - Trace Connector Pin 1
* TRACED0 PE3 - nLED_RED - Trace Connector Pin 3
* TRACED1 PE4 - nLED_GREEN - Trace Connector Pin 5
* TRACED2 PE5 - nLED_BLUE - Trace Connector Pin 7
* TRACED3 PE6 - nARMED - Trace Connector Pin 8
*/
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */
#if !defined(TRACE_PINS)
# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
# define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
# define GPIO_nLED_BLUE /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5)
# define BOARD_HAS_CONTROL_STATUS_LEDS 1
# define BOARD_OVERLOAD_LED LED_RED
# define BOARD_ARMED_STATE_LED LED_BLUE
#else
# define GPIO_TRACECLK1 (GPIO_TRACECLK |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2)
# define GPIO_TRACED0 (GPIO_TRACED0_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3)
# define GPIO_TRACED1 (GPIO_TRACED1_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4)
# define GPIO_TRACED2 (GPIO_TRACED2_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5)
# define GPIO_TRACED3 (GPIO_TRACED3_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6)
//#define GPIO_TRACESWO //(GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3)
# undef BOARD_HAS_CONTROL_STATUS_LEDS
# undef BOARD_OVERLOAD_LED
# undef BOARD_ARMED_STATE_LED
# define GPIO_nLED_RED GPIO_TRACED0
# define GPIO_nLED_GREEN GPIO_TRACED1
# define GPIO_nLED_BLUE GPIO_TRACED2
# define GPIO_nARMED GPIO_TRACED3
# define GPIO_nARMED_INIT GPIO_TRACED3
#endif
/* SPI */
#define SPI6_nRESET_EXTERNAL1 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN10)
#define GPIO_SYNC /* PE9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_100MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9)
/* I2C busses */
/* Devices on the onboard buses.
*
* Note that these are unshifted addresses.
*/
#define GPIO_I2C2_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|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 ADC1_CH(n) (n)
/* N.B. there is no offset mapping needed for ADC3 because */
#define ADC3_CH(n) (n)
/* We are only use ADC3 for REV/VER.
* ADC3_6V6 and ADC3_3V3 are mapped back to ADC1
* To do this We are relying on PC2_C, PC3_C being connected to PC2, PC3
* respectively by the SYSCFG_PMCR default of setting for PC3SO PC2SO PA1SO
* PA0SO of 0.
*
* 0 Analog switch closed (pads are connected through the analog switch)
*
* So ADC3_INP0 is GPIO_ADC123_INP12
* ADC3_INP1 is GPIO_ADC12_INP13
*/
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
#define PX4_ADC_GPIO \
/* PA0 */ GPIO_ADC1_INP16, \
/* PA4 */ GPIO_ADC12_INP18, \
/* PB0 */ GPIO_ADC12_INP9, \
/* PB1 */ GPIO_ADC12_INP5, \
/* PC2 */ GPIO_ADC123_INP12, \
/* PC3 */ GPIO_ADC12_INP13, \
/* PF12 */ GPIO_ADC1_INP6, \
/* PH3 */ GPIO_ADC3_INP14, \
/* PH4 */ GPIO_ADC3_INP15
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(16)
#define ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL /* PA4 */ ADC1_CH(18)
#define ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL /* PB0 */ ADC1_CH(9)
#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5)
#define ADC_ADC3_6V6_CHANNEL /* PC2 */ ADC3_CH(12)
#define ADC_ADC3_3V3_CHANNEL /* PC3 */ ADC3_CH(13)
#define ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL /* PF12 */ ADC1_CH(6)
#define ADC_HW_VER_SENSE_CHANNEL /* PH3 */ ADC3_CH(14)
#define ADC_HW_REV_SENSE_CHANNEL /* PH4 */ ADC3_CH(15)
#define ADC_CHANNELS \
((1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL) | \
(1 << ADC_SCALED_V5_CHANNEL) | \
(1 << ADC_ADC3_6V6_CHANNEL) | \
(1 << ADC_ADC3_3V3_CHANNEL)) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define HW_REV_VER_ADC_BASE STM32_ADC3_BASE
#define SYSTEM_ADC_BASE STM32_ADC1_BASE
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15
#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14
#define HW_INFO_INIT {'V','6','X','x', 'x',0}
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2 // Rev 0 and Rev 3 Sensor sets
// Base/FMUM
#define V6X00 HW_VER_REV(0x0,0x0) // FMUV6X, Rev 0
#define V6X01 HW_VER_REV(0x0,0x1) // FMUV6X, BMI388 I2C2 Rev 1
#define V6X03 HW_VER_REV(0x0,0x3) // FMUV6X, Sensor Set Rev 3
#define V6X04 HW_VER_REV(0x0,0x4) // FMUV6X, Sensor Set Rev 4
#define V6X10 HW_VER_REV(0x1,0x0) // NO PX4IO, Rev 0
#define V6X13 HW_VER_REV(0x1,0x3) // NO PX4IO, Sensor Set Rev 3
#define V6X14 HW_VER_REV(0x1,0x4) // NO PX4IO, Sensor Set Rev 4
#define V6X40 HW_VER_REV(0x4,0x0) // FMUV6X, HB CM4 base Rev 0
#define V6X41 HW_VER_REV(0x4,0x1) // FMUV6X, BMI388 I2C2 HB CM4 base Rev 1
#define V6X43 HW_VER_REV(0x4,0x3) // FMUV6X, Sensor Set HB CM4 base Rev 3
#define V6X44 HW_VER_REV(0x4,0x4) // FMUV6X, Sensor Set HB CM4 base Rev 4
#define V6X50 HW_VER_REV(0x5,0x0) // FMUV6X, HB Mini Rev 0
#define V6X51 HW_VER_REV(0x5,0x1) // FMUV6X, BMI388 I2C2 HB Mini Rev 1
#define V6X53 HW_VER_REV(0x5,0x3) // FMUV6X, Sensor Set HB Mini Rev 3
#define V6X54 HW_VER_REV(0x5,0x4) // FMUV6X, Sensor Set HB Mini Rev 4
/* HEATER
* PWM in future
*/
#define GPIO_HEATER_OUTPUT /* PB10 T2CH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true))
/* PE6 is nARMED
* The GPIO will be set as input while not armed HW will have external HW Pull UP.
* While armed it shall be configured at a GPIO OUT set LOW
*/
#if !defined(TRACE_PINS)
#define GPIO_nARMED_INIT /* PE6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN6)
#define GPIO_nARMED /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6)
#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT)
#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED)
#endif
/* PWM
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 9
/* Power supply control and monitoring GPIOs */
#define GPIO_nPOWER_IN_A /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1)
#define GPIO_nPOWER_IN_B /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2)
#define GPIO_nPOWER_IN_C /* PG3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN3)
#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */
#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */
#define BOARD_NUMBER_BRICKS 2
#define BOARD_NUMBER_DIGITAL_BRICKS 2
#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */
#define GPIO_VDD_5V_PERIPH_nEN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4)
#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN15)
#define GPIO_VDD_5V_HIPOWER_nEN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10)
#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13)
#define GPIO_VDD_3V3_SENSORS4_EN /* PG8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8)
#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2)
#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
/* Spare GPIO */
#define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6)
#define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15)
/* ETHERNET GPIO */
#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15)
/* NFC GPIO */
#define GPIO_NFC_GPIO /* PC0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN0)
/* Define True logic Power Control in arch agnostic form */
#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true))
#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true))
#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true))
#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true))
#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN)
#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true))
#define VDD_3V3_ETH_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_ETH_POWER_EN, (on_true))
/* Tone alarm output */
#define TONE_ALARM_TIMER 14 /* Timer 14 */
#define TONE_ALARM_CHANNEL 1 /* PF9 GPIO_TIM14_CH1OUT_2 */
#define GPIO_BUZZER_1 /* PF9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9)
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
#define GPIO_TONE_ALARM GPIO_TIM14_CH1OUT_2
/* USB OTG FS
*
* PA9 OTG_FS_VBUS VBUS sensing
*/
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
/* High-resolution timer */
#define HRT_TIMER 8 /* use timer8 for the HRT */
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
/* Input Capture Channels. */
#define INPUT_CAP1_TIMER 1
#define INPUT_CAP1_CHANNEL /* T1C2 */ 2
#define GPIO_INPUT_CAP1 /* PE11 */ GPIO_TIM1_CH2IN
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
#define PWMIN_TIMER 4
#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2
#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN_2
/* Safety Switch is HW version dependent on having an PX4IO
* So we init to a benign state with the _INIT definition
* and provide the the non _INIT one for the driver to make a run time
* decision to use it.
*/
#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN10)
#define GPIO_nSAFETY_SWITCH_LED_OUT /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */
#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT
#define GPIO_SAFETY_SWITCH_IN /* PF5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN5)
/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */
#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */
/* Power switch controls ******************************************************/
#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true)
/*
* FMUv6X has a separate RC_IN
*
* GPIO PPM_IN on PI5 T8CH1
* SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7
* Inversion is possible in the UART and can drive GPIO PPM_IN as an output
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */
#define SDIO_MINOR 0
/* 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
*/
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \
!defined(CONFIG_BOARD_INITTHREAD)
# warning SDIO initialization cannot be perfomed on the IDLE thread
#endif
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
* provides the true logic GPIO BOARD_ADC_xxxx macros.
*/
#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS))
#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID))
/* FMUv6X never powers off the Servo rail */
#define BOARD_ADC_SERVO_VALID (1)
#if !defined(BOARD_HAS_LTC44XX_VALIDS) || BOARD_HAS_LTC44XX_VALIDS == 0
# define BOARD_ADC_BRICK1_VALID (1)
# define BOARD_ADC_BRICK2_VALID (0)
#elif BOARD_HAS_LTC44XX_VALIDS == 1
# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
# define BOARD_ADC_BRICK2_VALID (0)
#elif BOARD_HAS_LTC44XX_VALIDS == 2
# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID))
#elif BOARD_HAS_LTC44XX_VALIDS == 3
# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID))
# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID))
#elif BOARD_HAS_LTC44XX_VALIDS == 4
# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID))
# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID))
# define BOARD_ADC_BRICK4_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK4_VALID))
#else
# error Unsupported BOARD_HAS_LTC44XX_VALIDS value
#endif
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC))
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC))
/* 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
#if defined(TRACE_PINS)
#define GPIO_TRACE \
GPIO_TRACECLK1, \
GPIO_TRACED0, \
GPIO_TRACED1, \
GPIO_TRACED2, \
GPIO_TRACED3
#else
#define GPIO_TRACE (GPIO_OUTPUT|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2)
#endif
#define PX4_GPIO_INIT_LIST { \
GPIO_TRACE, \
PX4_ADC_GPIO, \
GPIO_HW_VER_REV_DRIVE, \
GPIO_CAN1_TX, \
GPIO_CAN1_RX, \
GPIO_CAN2_TX, \
GPIO_CAN2_RX, \
GPIO_HEATER_OUTPUT, \
GPIO_nPOWER_IN_A, \
GPIO_nPOWER_IN_B, \
GPIO_nPOWER_IN_C, \
GPIO_VDD_5V_PERIPH_nEN, \
GPIO_VDD_5V_PERIPH_nOC, \
GPIO_VDD_5V_HIPOWER_nEN, \
GPIO_VDD_5V_HIPOWER_nOC, \
GPIO_VDD_3V3_SENSORS4_EN, \
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
GPIO_VDD_3V3_SD_CARD_EN, \
GPIO_PD15, \
GPIO_SYNC, \
SPI6_nRESET_EXTERNAL1, \
GPIO_ETH_POWER_EN, \
GPIO_NFC_GPIO, \
GPIO_TONE_ALARM_IDLE, \
GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \
GPIO_SAFETY_SWITCH_IN, \
GPIO_PG6, \
GPIO_nARMED_INIT \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define PX4_I2C_BUS_MTD 4,5
#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 PX4FMU 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

View File

@ -0,0 +1,85 @@
/****************************************************************************
*
* Copyright (c) 2019, 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/gpio.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 pins */
const uint32_t list[] = PX4_GPIO_INIT_LIST;
for (size_t gpio = 0; gpio < arraySize(list); gpio++) {
if (list[gpio] != 0) {
px4_arch_configgpio(list[gpio]);
}
}
/* 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();
}

View File

@ -0,0 +1,128 @@
/****************************************************************************
*
* Copyright (C) 2012 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 px4fmu_can.c
*
* Board-specific CAN functions.
*/
#ifdef CONFIG_CAN
#include <errno.h>
#include <debug.h>
#include <nuttx/can/can.h>
#include <arch/board/board.h>
#include "chip.h"
#include "arm_arch.h"
#include "chip.h"
#include "stm32_can.h"
#include "board_config.h"
#ifdef CONFIG_CAN
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Configuration ********************************************************************/
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
# undef CONFIG_STM32_CAN2
#endif
#ifdef CONFIG_STM32_CAN1
# define CAN_PORT 1
#else
# define CAN_PORT 2
#endif
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
int can_devinit(void);
/************************************************************************************
* Name: can_devinit
*
* Description:
* All STM32 architectures must provide the following interface to work with
* examples/can.
*
************************************************************************************/
int can_devinit(void)
{
static bool initialized = false;
struct can_dev_s *can;
int ret;
/* Check if we have already initialized */
if (!initialized) {
/* Call stm32_caninitialize() to get an instance of the CAN interface */
can = stm32_caninitialize(CAN_PORT);
if (can == NULL) {
canerr("ERROR: Failed to get CAN interface\n");
return -ENODEV;
}
/* Register the CAN driver at "/dev/can0" */
ret = can_register("/dev/can0", can);
if (ret < 0) {
canerr("ERROR: can_register failed: %d\n", ret);
return ret;
}
/* Now we are initialized */
initialized = true;
}
return OK;
}
#endif
#endif /* CONFIG_CAN */

View File

@ -0,0 +1,128 @@
/*
* hw_config.h
*
* Created on: May 17, 2015
* Author: david_s5
*/
#ifndef HW_CONFIG_H_
#define HW_CONFIG_H_
/****************************************************************************
* 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,115200"
#define BOOT_DELAY_ADDRESS 0x000001a0
#define BOARD_TYPE 57
#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_GREEN // GREEN
#define BOARD_LED_ON 0
#define BOARD_LED_OFF 1
#define SERIAL_BREAK_DETECT_DISABLED 1
/*
* Uncommenting this allows to force the bootloader through
* a PWM output pin. As this can accidentally initialize
* an ESC prematurely, it is not recommended. This feature
* has not been used and hence defaults now to off.
*
* # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14)
* # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11)
*
* # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
* # define BOARD_POWER_ON 1
* # define BOARD_POWER_OFF 0
* # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power)
*
*/
#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
#endif /* HW_CONFIG_H_ */

View File

@ -0,0 +1,41 @@
/****************************************************************************
*
* 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 <px4_arch/i2c_hw_description.h>
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusExternal(1),
initI2CBusExternal(2),
initI2CBusExternal(3),
initI2CBusInternal(4),
};

View File

@ -0,0 +1,277 @@
/****************************************************************************
*
* Copyright (c) 2012-2022 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
*
* PX4FMU-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 initialization.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include "board_config.h"
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <syslog.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <nuttx/mm/gran.h>
#include <chip.h>
#include <stm32_uart.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_determine_hw_info.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/*
* 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);
__END_DECLS
/************************************************************************************
* Name: board_peripheral_reset
*
* Description:
*
************************************************************************************/
__EXPORT void board_peripheral_reset(int ms)
{
/* set the peripheral rails off */
VDD_5V_HIPOWER_EN(false);
VDD_5V_PERIPH_EN(false);
board_control_spi_sensors_power(false, 0xffff);
VDD_3V3_SENSORS4_EN(false);
bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN();
/* Keep Spektum on to discharge rail*/
VDD_3V3_SPEKTRUM_POWER_EN(false);
/* wait for the peripheral rail to reach GND */
usleep(ms * 1000);
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
/* re-enable power */
/* switch the peripheral rail back on */
VDD_3V3_SPEKTRUM_POWER_EN(last);
board_control_spi_sensors_power(true, 0xffff);
VDD_3V3_SENSORS4_EN(true);
VDD_5V_HIPOWER_EN(true);
VDD_5V_PERIPH_EN(true);
}
/************************************************************************************
* 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)
{
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
/* configure USB interfaces */
stm32_usbinitialize();
VDD_3V3_ETH_POWER_EN(true);
}
/****************************************************************************
* 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; the meaning of the argument is a contract
* between the board-specific initalization logic and the the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
*
* 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)
{
/* Power on Interfaces */
VDD_5V_PERIPH_EN(true);
VDD_5V_HIPOWER_EN(true);
VDD_3V3_SENSORS4_EN(true);
VDD_3V3_SPEKTRUM_POWER_EN(true);
/* Need hrt running before using the ADC */
px4_platform_init();
if (OK == board_determine_hw_info()) {
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
board_get_hw_type_name());
} else {
syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n");
}
stm32_spiinitialize();
board_spi_reset(10, 0xffff);
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
}
#if defined(SERIAL_HAVE_RXDMA)
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
static struct hrt_call serial_dma_call;
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
#endif
/* initial LED state */
drv_led_start();
led_off(LED_RED);
led_on(LED_GREEN); // Indicate Power.
led_off(LED_BLUE);
if (board_hardfault_init(2, true) != 0) {
led_on(LED_RED);
}
// Ensure Power is off for > 10 mS
usleep(15 * 1000);
VDD_3V3_SD_CARD_EN(true);
usleep(500 * 1000);
#ifdef CONFIG_MMCSD
int ret = stm32_sdio_initialize();
if (ret != OK) {
led_on(LED_RED);
}
#endif /* CONFIG_MMCSD */
/* Configure the HW based on the manifest */
px4_platform_configure();
return OK;
}

View File

@ -0,0 +1,235 @@
/****************************************************************************
*
* Copyright (c) 2013 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 px4fmu2_led.c
*
* PX4FMU 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
#ifdef CONFIG_ARCH_LEDS
static bool nuttx_owns_leds = true;
// B R S G
// 0 1 2 3
static const uint8_t xlatpx4[] = {1, 2, 4, 0};
# define xlat(p) xlatpx4[(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
GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4
};
#else
# define xlat(p) (p)
static uint32_t g_ledmap[] = {
GPIO_nLED_BLUE, // Indexed by LED_BLUE
GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER
0, // Indexed by LED_SAFETY (defaulted to an input)
GPIO_nLED_GREEN, // Indexed by LED_GREEN
};
#endif
__EXPORT void led_init(void)
{
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)));
}
#ifdef CONFIG_ARCH_LEDS
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_autoled_initialize
****************************************************************************/
void board_autoled_initialize(void)
{
led_init();
}
/****************************************************************************
* Name: board_autoled_on
****************************************************************************/
void board_autoled_on(int led)
{
if (!nuttx_owns_leds) {
return;
}
switch (led) {
default:
break;
case LED_HEAPALLOCATE:
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_IRQSENABLED:
phy_set_led(BOARD_LED_BLUE, false);
phy_set_led(BOARD_LED_GREEN, true);
break;
case LED_STACKCREATED:
phy_set_led(BOARD_LED_GREEN, true);
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_INIRQ:
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_SIGNAL:
phy_set_led(BOARD_LED_GREEN, true);
break;
case LED_ASSERTION:
phy_set_led(BOARD_LED_RED, true);
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_PANIC:
phy_set_led(BOARD_LED_RED, true);
break;
case LED_IDLE : /* IDLE */
phy_set_led(BOARD_LED_RED, true);
break;
}
}
/****************************************************************************
* Name: board_autoled_off
****************************************************************************/
void board_autoled_off(int led)
{
if (!nuttx_owns_leds) {
return;
}
switch (led) {
default:
break;
case LED_SIGNAL:
phy_set_led(BOARD_LED_GREEN, false);
break;
case LED_INIRQ:
phy_set_led(BOARD_LED_BLUE, false);
break;
case LED_ASSERTION:
phy_set_led(BOARD_LED_RED, false);
phy_set_led(BOARD_LED_BLUE, false);
break;
case LED_PANIC:
phy_set_led(BOARD_LED_RED, false);
break;
case LED_IDLE : /* IDLE */
phy_set_led(BOARD_LED_RED, false);
break;
}
}
#endif /* CONFIG_ARCH_LEDS */

View File

@ -0,0 +1,202 @@
/****************************************************************************
*
* Copyright (c) 2022 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[] = {
{
// PX4_MFT_PX4IO
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
// PX4_MFT_USB
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
// PX4_MFT_CAN2
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
};
static const px4_hw_mft_item_t hw_mft_list_v0610[] = {
{
// PX4_MFT_PX4IO
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
{
// PX4_MFT_USB
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
// PX4_MFT_CAN2
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
};
static const px4_hw_mft_item_t hw_mft_list_v0650[] = {
{
// PX4_MFT_PX4IO
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_unknown,
},
{
// PX4_MFT_USB
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
// PX4_MFT_CAN2
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
};
static px4_hw_mft_list_entry_t mft_lists[] = {
// ver_rev
{V6X00, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)},
{V6X01, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2
{V6X03, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 3
{V6X40, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // HB CM4 base
{V6X41, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2 HB CM4 base
{V6X43, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, HB CM4 base Sensor Set 3
{V6X44, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, HB CM4 base Sensor Set 4
{V6X50, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // HB Mini
{V6X51, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2 HB Mini
{V6X53, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 3
{V6X54, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 4
{V6X10, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO
{V6X13, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO BMP388 moved to I2C2, Sensor Set 3
{V6X04, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 4
{V6X14, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO BMP388 moved to I2C2, Sensor Set 4
};
/************************************************************************************
* 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() << 8;
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 %4" 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;
}

View File

@ -0,0 +1,103 @@
/****************************************************************************
*
* Copyright (C) 2022 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 <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_mft_device_t i2c3 = { // 24LC64T on Base 8K 32 X 256
.bus_type = px4_mft_device_t::I2C,
.devid = PX4_MK_I2C_DEVID(3, 0x51)
};
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_entry_t base_eeprom = {
.device = &i2c3,
.npart = 2,
.partd = {
{
.type = MTD_MFT,
.path = "/fs/mtd_mft",
.nblocks = 248
},
{
.type = MTD_NET,
.path = "/fs/mtd_net",
.nblocks = 8 // 256 = 32 * 8
}
},
};
static const px4_mtd_manifest_t board_mtd_config = {
.nconfigs = 2,
.entries = {
&fmum_fram,
&base_eeprom,
}
};
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;
}

View File

@ -0,0 +1,177 @@
/****************************************************************************
*
* 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 */

View File

@ -0,0 +1,86 @@
/****************************************************************************
*
* Copyright (C) 2020, 2022 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_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = {
initSPIHWVersion(HW_VER_REV(0, 0), {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}),
initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}),
}, {GPIO::PortF, GPIO::Pin4}),
initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}),
}, {GPIO::PortE, GPIO::Pin7}),
// initSPIBus(SPI::Bus::SPI4, {
// // no devices
// TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h
// }, {GPIO::PortG, GPIO::Pin8}),
initSPIBus(SPI::Bus::SPI5, {
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7})
}),
initSPIBusExternal(SPI::Bus::SPI6, {
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}),
initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}),
}),
}),
initSPIHWVersion(HW_VER_REV(0, 3), {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}),
initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}),
}, {GPIO::PortF, GPIO::Pin4}),
initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}),
}, {GPIO::PortE, GPIO::Pin7}),
// initSPIBus(SPI::Bus::SPI4, {
// // no devices
// TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h
// }, {GPIO::PortG, GPIO::Pin8}),
initSPIBus(SPI::Bus::SPI5, {
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7})
}),
initSPIBusExternal(SPI::Bus::SPI6, {
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}),
initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}),
}),
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw);

View File

@ -0,0 +1,80 @@
/****************************************************************************
*
* Copyright (C) 2012 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>
/* Timer allocation
*
* TIM5_CH4 T FMU_CH1
* TIM5_CH3 T FMU_CH2
* TIM5_CH2 T FMU_CH3
* TIM5_CH1 T FMU_CH4
*
* TIM4_CH2 T FMU_CH5
* TIM4_CH3 T FMU_CH6
*
* TIM12_CH1 T FMU_CH7
* TIM12_CH2 T FMU_CH8
*
* TIM1_CH2 T FMU_CAP1 < Capture
* TIM1_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT
* TIM1_CH1 T SPIX_SYNC > Pulse or GPIO strobe
*
* TIM2_CH3 T HEATER > PWM OUT or GPIO
*
* TIM14_CH1 T BUZZER_1 - Driven by other driver
* TIM8_CH1_IN T FMU_PPM_INPUT - Sampled byt HRT by other driver
*/
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer5, DMA{DMA::Index1}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
initIOTimer(Timer::Timer12),
initIOTimer(Timer::Timer1),
initIOTimer(Timer::Timer2),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}),
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}),
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}),
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}),
initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}),
initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}),
initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}),
};
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
initIOTimerChannelMapping(io_timers, timer_io_channels);

View File

@ -0,0 +1,105 @@
/****************************************************************************
*
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* 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 px4fmu_usb.c
*
* Board-specific USB functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
#include <arm_arch.h>
#include <chip.h>
#include <stm32_gpio.h>
#include <stm32_otg.h>
#include "board_config.h"
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the PX4FMU 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);
}

View File

@ -140,8 +140,7 @@ CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -162,8 +162,7 @@ CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

View File

@ -1,5 +1,5 @@
CONFIG_PLATFORM_POSIX=y
CONFIG_BOARD_LINUX=y
CONFIG_BOARD_LINUX_TARGET=y
CONFIG_BOARD_TOOLCHAIN="arm-linux-gnueabihf"
CONFIG_BOARD_ARCHITECTURE="cortex-a8"
CONFIG_BOARD_TESTING=y

View File

@ -126,8 +126,7 @@ CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

View File

@ -125,8 +125,7 @@ CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

View File

@ -108,8 +108,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

View File

@ -139,8 +139,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -111,6 +111,7 @@ 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 */
@ -186,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > AXI_SRAM AT > FLASH
/* 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(.);

View File

@ -138,8 +138,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -111,6 +111,7 @@ 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 */
@ -186,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > AXI_SRAM AT > FLASH
/* 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(.);

View File

@ -10,3 +10,4 @@ CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_TEST_PPM=y
CONFIG_SYSTEMCMDS_MICROBENCH=y
CONFIG_SYSTEMCMDS_BL_UPDATE=n

View File

@ -140,8 +140,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -187,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > AXI_SRAM AT > FLASH
/* 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(.);

View File

@ -138,8 +138,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -12,3 +12,4 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_TEST_PPM=y
CONFIG_SYSTEMCMDS_MICROBENCH=y
CONFIG_SYSTEMCMDS_BL_UPDATE=n

View File

@ -141,8 +141,7 @@ CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -120,8 +120,7 @@ CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@ -158,7 +157,7 @@ CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI1_DMA=y
CONFIG_STM32_SPI1_DMA_BUFFER=1024
CONFIG_STM32_SPI1_DMA_BUFFER=512
CONFIG_STM32_SPI2=y
CONFIG_STM32_SPI2_DMA=y
CONFIG_STM32_SPI3=y

View File

@ -1,5 +1,5 @@
CONFIG_PLATFORM_POSIX=y
CONFIG_BOARD_LINUX=y
CONFIG_BOARD_LINUX_TARGET=y
CONFIG_BOARD_TOOLCHAIN="arm-linux-gnueabihf"
CONFIG_BOARD_ARCHITECTURE="cortex-a53"
CONFIG_BOARD_TESTING=y

View File

@ -122,8 +122,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

View File

@ -108,8 +108,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

View File

@ -140,8 +140,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -109,16 +109,17 @@
MEMORY
{
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
flash (rx) : ORIGIN = 0x08020000, LENGTH = 1920K
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
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)
@ -156,7 +157,7 @@ SECTIONS
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
} > FLASH
/*
* Init functions (static constructors and the like)
@ -165,17 +166,17 @@ SECTIONS
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
} > FLASH
.ARM.extab : {
*(.ARM.extab*)
} > flash
} > FLASH
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
} > FLASH
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
@ -186,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
/* 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(.);
@ -195,7 +201,7 @@ SECTIONS
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
} > AXI_SRAM
/* Emit the the D3 power domain section for locating BDMA data */
@ -204,7 +210,7 @@ SECTIONS
*(.sram4)
. = ALIGN(4);
_sram4_heap_start = ABSOLUTE(.);
} > sram4
} > SRAM4
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }

View File

@ -140,8 +140,7 @@ CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y

View File

@ -139,8 +139,7 @@ CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -109,16 +109,17 @@
MEMORY
{
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
flash (rx) : ORIGIN = 0x08020000, LENGTH = 1792K /* params in last sector */
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
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K /* params in last sector */
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)
@ -156,7 +157,7 @@ SECTIONS
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
} > FLASH
/*
* Init functions (static constructors and the like)
@ -165,17 +166,17 @@ SECTIONS
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
} > FLASH
.ARM.extab : {
*(.ARM.extab*)
} > flash
} > FLASH
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
} > FLASH
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
@ -186,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
/* 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(.);
@ -195,7 +201,7 @@ SECTIONS
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
} > AXI_SRAM
/* Emit the the D3 power domain section for locating BDMA data */
@ -204,7 +210,7 @@ SECTIONS
*(.sram4)
. = ALIGN(4);
_sram4_heap_start = ABSOLUTE(.);
} > sram4
} > SRAM4
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }

View File

@ -140,8 +140,7 @@ CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -126,8 +126,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_PASSTHRU_UBLOX=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -130,8 +130,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -34,7 +34,7 @@
*
****************************************************************************/
/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory.
/* 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:
*
@ -59,8 +59,8 @@
* 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
* 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.
@ -109,16 +109,17 @@
MEMORY
{
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
flash (rx) : ORIGIN = 0x08020000, LENGTH = 1920K
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
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)
@ -156,7 +157,7 @@ SECTIONS
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
} > FLASH
/*
* Init functions (static constructors and the like)
@ -165,17 +166,17 @@ SECTIONS
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
} > FLASH
.ARM.extab : {
*(.ARM.extab*)
} > flash
} > FLASH
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
} > FLASH
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
@ -186,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
/* 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(.);
@ -195,7 +201,7 @@ SECTIONS
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
} > AXI_SRAM
/* Emit the the D3 power domain section for locating BDMA data */
@ -204,7 +210,7 @@ SECTIONS
*(.sram4)
. = ALIGN(4);
_sram4_heap_start = ABSOLUTE(.);
} > sram4
} > SRAM4
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }

View File

@ -138,8 +138,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC2_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -140,8 +140,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC2_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -109,16 +109,17 @@
MEMORY
{
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
flash (rx) : ORIGIN = 0x08020000, LENGTH = 1920K
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
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)
@ -157,7 +158,7 @@ SECTIONS
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
} > FLASH
/*
* Init functions (static constructors and the like)
@ -166,17 +167,17 @@ SECTIONS
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
} > FLASH
.ARM.extab : {
*(.ARM.extab*)
} > flash
} > FLASH
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
} > FLASH
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
@ -187,7 +188,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
/* 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(.);
@ -196,7 +202,7 @@ SECTIONS
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
} > AXI_SRAM
/* Emit the the D3 power domain section for locating BDMA data */
@ -205,7 +211,7 @@ SECTIONS
*(.sram4)
. = ALIGN(4);
_sram4_heap_start = ABSOLUTE(.);
} > sram4
} > SRAM4
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }

View File

@ -11,7 +11,7 @@
# CONFIG_STM32H7_SYSCFG is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/mro/ctrl-zero-classic/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"

View File

@ -140,8 +140,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -187,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > AXI_SRAM AT > FLASH
/* 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(.);
@ -207,7 +212,6 @@ SECTIONS
_sram4_heap_start = ABSOLUTE(.);
} > SRAM4
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
@ -221,13 +225,4 @@ SECTIONS
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
.ramfunc : {
_sramfuncs = .;
*(.ramfunc .ramfunc.*)
. = ALIGN(4);
_eramfuncs = .;
} > ITCM_RAM AT > FLASH
_framfuncs = LOADADDR(.ramfunc);
}

View File

@ -139,8 +139,7 @@ CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -139,8 +139,7 @@ CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

View File

@ -141,8 +141,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y

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