Compare commits

...

157 Commits

Author SHA1 Message Date
Vincent Poon f75a92d199 Change FMU-v6x REV 6 IMU Order
Change IMU Order, make adis16470 in 1st priority.
2024-03-19 05:35:30 +13:00
David Sidrane f6ec71d39f px4_fmu-v6x:Add Sensor set 8 2024-03-19 05:35:30 +13:00
alexklimaj 247067d392 boards: arkv6x migrate to split versioning 2024-03-19 05:35:30 +13:00
David Sidrane f69c6354dd px4_fmu-v5x:Use BOARD_HAS_HW_SPLIT_VERSIONING & common PAB manifest 2024-03-19 05:35:30 +13:00
David Sidrane 23d8b3cf25 px4_fmu-v6x:rc.board_sensors Use BOARD_HAS_HW_SPLIT_VERSIONING 2024-03-19 05:35:30 +13:00
David Sidrane 0c1b5e88c5 px4_fmu-v6x:HAVE_PM2 set by PX4_MFT_PM2 in manifest 2024-03-19 05:35:30 +13:00
David Sidrane e5f4adaa2d PX4:ver Add base type compare 2024-03-19 05:35:30 +13:00
David Sidrane 3e0290b084 ROMFS:netman update - dependent on PX4_MFT_ETHERNET not board type 2024-03-19 05:35:30 +13:00
David Sidrane a2db688f4b px4_fmu_v6x:Use common PAB manifest 2024-03-19 05:35:30 +13:00
David Sidrane 4536f3b2e4 PX4:common add PAB manifest
PX4:common add PAB manifest with V5X bases
2024-03-19 05:35:30 +13:00
David Sidrane 4b5a709e27 PX4:Extend manifest types & add CLI query 2024-03-19 05:35:30 +13:00
David Sidrane 4339833696 px4_fmu-v6x:Use BOARD_HAS_HW_SPLIT_VERSIONING 2024-03-19 05:35:30 +13:00
David Sidrane 4409f82efc stm Support BOARD_HAS_HW_SPLIT_VERSIONING 2024-03-19 05:35:30 +13:00
David Sidrane f916aeddea PX4:comon Support BOARD_HAS_HW_SPLIT_VERSIONING 2024-03-19 05:35:30 +13:00
David Sidrane b70381584c boards:Needing Migration to BOARD_HAS_HW_SPLIT_VERSIONING 2024-03-19 05:35:30 +13:00
David Sidrane 3691b132b2 px4_fmuv6x:Fit Rev6 Sensors 2024-03-19 05:35:30 +13:00
David Sidrane 4901edb5a4 px4_fmu-v6:Add Sensor Set Rev 6 2024-03-19 05:35:30 +13:00
David Sidrane c5e2d9d871 px4_fmu-v6x:Rev 6 Sensors omit starting icm42688p, icm42670p, icm20649, icm20602 2024-03-19 05:35:30 +13:00
Julian Oes 50b85ca831 kakute: disable some EKF2 features
To save flash.

Signed-off-by: Julian Oes <julian@oes.ch>
2024-03-04 21:28:23 -05:00
Julian Oes 61eb53dc75 kakuteh7: use EKF2 by default
Signed-off-by: Julian Oes <julian@oes.ch>
2024-03-04 21:28:23 -05:00
Beat Küng 9687324778 gps: update submodule 2024-02-15 10:09:28 -05:00
Silvan Fuhrer b303e9517f
param translation: fix too early return false (#22729)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2024-02-07 12:41:23 +01:00
Beat Küng 8df02de9fd commander: send ack for VEHICLE_CMD_DO_SET_ACTUATOR 2024-02-02 09:38:48 -05:00
Beat Küng b0e86ba364 fix FunctionActuatorSet: if a param is set to NaN, it should be ignored
MAVLink spec: https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR
Previously, a command was overwriting all other indexes.
2024-02-02 09:38:48 -05:00
Julian Oes 454a987568 fmu-6x: fix Telem2 without flow control
When flow control is used together with DMA, we need to add a pulldown
to CTS. Without it, it assumes flow control and gets stuck when
CTS is not connected.

Signed-off-by: Julian Oes <julian@oes.ch>
2024-02-01 21:11:57 -05:00
Matthias Grob beb834af2b fmu-v6x: add crossfire UART driver 2024-01-11 11:04:51 -05:00
MaEtUgR 6eb8d042e1 [AUTO COMMIT] update change indication 2023-12-22 09:46:09 +01:00
Matthias Grob d09aa8ade5 matrix: fix slice to slice assignment to do deep copy
To fix usage of a.xy() = b.xy() which should copy
the first two elements over into a and not act on a copy of a.
2023-12-22 09:46:09 +01:00
alexklimaj b50a9dac84 px4io: change not supported message to INFO instead of ERR 2023-12-12 20:48:28 -05:00
David Sidrane 73fa6e0c52 px4io:Add 'supported' command and uses it in rcS 2023-12-12 20:48:28 -05:00
Matthias Grob 968089bae4 ActuatorEffectivenessHelicopter: explicitly handle unsaturated case
This became necessary otherwise
the allocation reports saturation all
the time and the rate integrator doesn't work.
2023-12-12 14:41:59 -05:00
Silvan Fuhrer 43ba199c37
Navigator: same logic for VTOL_TAKEOFF as for TAKEOFF (#22519)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-11 14:35:56 +01:00
Silvan Fuhrer a536e3dfe2 TECS: init control params to reasonable values
The control params (eg min/max pitch) are used before they are
correctly set by TECS::update(). While this is an issue we should fix,
it also doesn't hurt to set them to more reasobale values (eg 30° limit).

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-08 16:26:10 +01:00
Silvan Fuhrer 5d433ddef7 TECS: make sure to constrain pitch to current min/max pitch
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-08 16:26:10 +01:00
Silvan Fuhrer 5928d7f067 TECS: init to airspeed filter to trim airspeed if airspeed-less
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-08 16:26:10 +01:00
Silvan Fuhrer 740bf63fa7 TECS: set _ratio_underspeed to 0 if airspeed disabled
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-12-08 16:26:10 +01:00
alexklimaj 634ad3893e flight mode manager: fix terrain hold 2023-11-21 18:12:14 +01:00
bresch 26109a2fe6 ekf2 rng kin: allow check to become true during horizontal motion
Even if there is some horizontal motion, a passing check should be
accepted as the terrain can be flat. However, the vehicle must not be
moving horizontally to invalidate the consistency as a change in terrain
can make the kinematic check temporarily fail.
2023-11-21 12:09:11 -05:00
bresch ff2441d73a ekf2-terrain: fix validity switching
Bug not present after 1.14
2023-11-21 12:09:11 -05:00
Julian Oes b15e57dd4f icm45686: fix dt (and usage command)
With the wrong dt, the flight behaviour was really poor and noisy, so
this fix is absolutely required.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-11-21 11:08:07 +13:00
bresch 9ab8970206 atune: initialize filter if not already initialized 2023-11-17 09:52:01 +01:00
Julian Oes c3ed50488f Remove SYS_USE_IO param
The param is not really required anymore with the actuator
configuration. Also, when it is set to 0, RC doesn't work for some
boards which would be nice to avoid.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-11-15 06:54:27 +13:00
Matthias Grob 6cdf09644e PositionSmoothing: fix corner altitude bug
During a round corner the L1 distance calculation
was only done in 2D and the z-axis coordinate
was directly coming from the next waypoint.
This lead to an unpredictable altitude profile
between two waypoints. Sometimes almost all
altitude difference was already covered during
the turn instead of going diagonally.
2023-11-10 19:32:21 +01:00
Julian Oes 4138ab0436 gps: update to latest release/1.14 branch
This sets the src/drivers/gps/devices submodule to the latest
release/1.14 branch. This fixes a potential issue with the Unicore M10
GPS driver, making sure the AGRICA message is requested.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-11-10 12:16:11 +13:00
Julian Oes e5d92c5195 mavlink: fix MAVLink message forwarding
This switches from the horribly intertwined ringbuffer implementation to
the new VariableLengthRingbuffer implementation.

By ditching the previous implementation, we fix MAVLink message
forwarding, which didn't work reliably. The reason it didn't work is
that multiple mavlink messages could be added but only one of them was
sent out because the buffer didn't keep track of the messages properly
and only read the first one.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-11-10 12:15:58 +13:00
Julian Oes 2edc3cf845 lib: add variable length ringbuffer
This adds a reusable class for a FIFO ringbuffer that accepts variable
length packets. It is using the Ringbuffer class internally.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-11-10 12:15:58 +13:00
Julian Oes 813494bc3d lib: add FIFO ringbuffer class
This adds a reusable class for a simple FIFO ringbuffer.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-11-10 12:15:58 +13:00
Julian Oes e9a142ac7d mavlink: properly set mission_type
This was defaulted to 0 before which messed with transmitting geofence
and rally items.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-11-10 12:15:05 +13:00
alexklimaj 40c9789e7d boards: arkv6x fix wrong pwm output values 2023-10-31 10:23:57 -04:00
Silvan Fuhrer b8c541dd72 TiltrotorEffectiveness: limit thrust axis tilt to z effectiveness scaling
During transition to FF, only allow update thrust axis up to 45° as with a high tilt angle
the effectiveness of the thrust axis in z is apporaching 0, and by that is increasing
the motor output to max.
Transition to HF: disable thrust axis tilting, and assume motors are vertical. This is to avoid
a thrust spike when the transition is initiated (as then the tilt is fully forward).

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-10-18 16:31:42 -04:00
Beniamino Pozzan 2d3238dfbe
[gz-bridge] fix GZ timeout for slow starting simulations (#22195)
Signed-off-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
2023-10-18 09:41:53 +02:00
Vincent Poon ad36b9add7 Fix Default Output Protocol - Airframe 4019_x500_v2
Remove "param set-default PWM_MAIN_TIM0 -4"
2023-10-08 10:43:22 +13:00
Julian Oes 13cb8ce4a8 cubepilot: fix 4. Orange+ variant
There was a missing then, and missing SPI definitions.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-10-06 08:02:22 +13:00
Julian Oes b4f425db56 cubepilot: Add support for 4. variant of Orange+
This adds support for the 4. hardware variant of the CubeOrange+
featuring 3 ICM45686.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-10-06 08:02:22 +13:00
Beat Küng e961b29c56 fix crsf_rc: prevent potential buffer overflow for unknown packets
The length check for unknown packets did not include PACKET_SIZE_TYPE_SIZE
and CRC_SIZE, and hence working_index could overflow CRSF_MAX_PACKET_LEN,
triggering invalid memory access further down in QueueBuffer_PeekBuffer.

Also the working_segment_size was wrong for unknown packets.

Credits for finding this go to @Pwn9uin.
2023-10-05 08:00:32 +02:00
Silvan Fuhrer 6e65478959
vfr_hud: fix throttle display for FW and show magnitude for 3D thrust (#22157)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-09-29 09:55:22 +02:00
Silvan Fuhrer 2f5aa92596 FW Position Controller: handle IDLE waypoints in FW_POSCTRL_MODE_AUTO, also with NAN setpoints
A setpoint of type IDLE can be published by Navigator without a valid position,
and should be handled in the auto function in FW_POSCTRL_MODE_AUTO. If it wouldn't be
handled there the controller would switch to mode FW_POSCTRL_MODE_OTHER, in which case
no attitude setpoint is published and the lower controllers would be stuck with the
last published value (incl. thrust).

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-09-21 16:23:08 -04:00
Silvan Fuhrer 080e16f0a6 FW Positon Controller: set references to 0 if not provided by local_position (#22101)
* FW Positon Controller: set altitude_ref to 0 if not provided by GPS

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>

* FW Positon Controller: set lat/lon reference to 0 if not provided in local_position

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>

---------

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-09-20 17:43:35 -04:00
Thomas Stastny 27e6a0d227 Commander: make sure unsupported do reposition command result is published
todo: need to consolidate the command ack strategy in this function
2023-09-19 19:16:02 -04:00
Thomas Stastny ff8663b0b1 Commander: dont accept reposition commands without the mode switch bit
avoids erroneous (unexpected) position setpoints when switching into hold from another mode
2023-09-19 19:16:02 -04:00
Thomas Stastny 3e68e806b8 loiter: only accept reposition setpoint if commanded within last 0.5 sec
guards against left over reposition commands (potentially set via geofence) from previous flights
2023-09-19 19:16:02 -04:00
Thomas Stastny 39351acbcb FixedwingPositionControl: initialize the airspeed slew rate controller with trim airspeed in the constructor 2023-09-19 19:15:41 -04:00
Daniel Agar 2c9b739814 drivers/optical_flow/paa3905: backup scheduling to fetch 0 flow
- this sensor provides a MOTION interrupt used for default scheduling, but we also need to publish
   zero flow information
2023-09-18 14:19:56 -04:00
Daniel Agar 5e8ee98bf9 sensors/vehicle_optical_flow: don't publish interval lower than configured rate 2023-09-18 14:19:56 -04:00
Daniel Agar d98f3554da drivers/optical_flow/paw3902: backup scheduling to fetch 0 flow
- this sensor provides a MOTION interrupt used for default scheduling, but we also need to publish
   zero flow information
2023-09-18 14:19:56 -04:00
Thomas Stastny 1f30b2168d FixedwingPositionControl: rework airspeed slew controller handling
- force initialize takeoff airspeed setpoint at start of takeoff modes
- force set airspeed constraints if slewed value is out of bounds
- always slew airspeed setpoints as long as inside constraints
- move target airspeed setpoint calculation into mode specific logic regions (hand vs runway)
2023-09-13 11:26:03 -04:00
Silvan Fuhrer 17177b3948 ROMFS: SITL plane_catapult: reduce FW_LAUN_AC_THLD to 10m/s/s to detect every throw
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-09-13 11:26:03 -04:00
Silvan Fuhrer ccef260f10 FW Pos Control: add in_takeoff_situation argument to adapt_airspeed_setpoint()
when we're in a takeoff situation, we only want to adapt the airspeed to
avoid accelerated stall due to load factor changes. Disable othre logic
like minimum ground speed, wind based adaption and airspeed slew rating.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-09-13 11:26:03 -04:00
Thomas Stastny 3c9c5f7184 FixedwingPositionControl: slightly simplify manual position control (use navigateLine() to be sure no turnaround)
make notes on odd things that are likely still wrong
2023-09-12 11:22:22 -04:00
Thomas Stastny 7316d50555 FixedwingPositionControl: revise navigateLine(), navigateBearing() and naivgatePathTangent() briefs 2023-09-12 11:22:22 -04:00
Thomas Stastny 97112a7d20 FixedwingPositionControl: forgot to rename input args in navigateWaypoints() declaration 2023-09-12 11:22:22 -04:00
Thomas Stastny cd9fd12e91 FixedwingPositionControl: reuse line() and waypoint() methods in navigateWaypoints() method 2023-09-12 11:22:22 -04:00
Thomas Stastny a3f1f0e846 FixedwingPositionControl: split out single waypoint following method
makes more clearly defined interfaces and behaviors. also cleaned up the controlAutoPosition() method
2023-09-12 11:22:22 -04:00
Thomas Stastny 37015c3dbe FixedwingPositionControl: track single point when no prev point exists for waypoint following
make sure correct local position setpoint output is logged
2023-09-12 11:22:22 -04:00
Thomas Stastny 7160da741d FixedwingPositionControl: correct navigation method param description typos 2023-09-12 11:22:22 -04:00
Thomas Stastny db48b04281 FixedwingPositionControl: follow (infinite) lines instead of waypoints during takeoff and landing 2023-09-12 11:22:22 -04:00
Thomas Stastny da8dcc4942 FixedwingPositionControl: handle degenerate tangent setpoint in navigatePathTangent() 2023-09-12 11:22:22 -04:00
Thomas Stastny 7c2c288c09 npfg: update signed track error state 2023-09-12 11:22:22 -04:00
Thomas Stastny 30870e50c0 FixedwingPositionControl: fix / clarify navigate waypoint logic 2023-09-12 11:22:22 -04:00
Julian Oes 28b018f9bd px4_fmu-v5_test: save flash by disabling fixedwing
Signed-off-by: Julian Oes <julian@oes.ch>
2023-09-12 11:22:04 -04:00
Julian Oes 3896df3e72 mavlink: improve readability
Co-authored-by: Matthias Grob <maetugr@gmail.com>
2023-09-12 11:22:04 -04:00
Julian Oes 56fcabf0b1 mavlink: Support voltages > 65v in battery status
If the measured voltage is more than 65v we need to split the voltage
over multiple cells in order to avoid overflowing the uint16. This is
according to the MAVLink spec.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-09-12 11:22:04 -04:00
Julian Oes 7b60737f9a mavlink: fix BATTERY_STATUS extension
The extension fields need to be 0 by default according to the MAVLink
spec. This is because extensions are 0 by default and need to be 0 when
unknown/unused for backwards compatibility.

The patch also simplifies the flow slightly in that it doesn't create a
temporary array but just fills in the cell voltages directly.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-09-12 11:22:04 -04:00
Julian Oes 440165809a 6x: fix internal mag rotation
From looking at the history the BMM150 rotation was initially 0. Then,
this was changed to 6 when the intent was to only change it for Skynode.

A bit later, the rotation was changed back to 0, but only for Skynode.

This tells me that rotation 0 was correct for all 6X including Skynode
all along.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-09-12 21:26:59 +12:00
Peter van der Perk d9fd67be3b [BACKPORT] MR-CANHUBK3 ADAP board support, add ADC support 2023-09-07 19:10:10 -04:00
alexklimaj 3cf205c4a6 ARKV6X update rev 2 heater default temp id 2023-09-05 13:09:45 -04:00
alexklimaj d54e488288 Add IIM42653 and ARKV6X Rev 2 2023-09-05 13:09:45 -04:00
Matthias Grob 70081652fe Tools/auterion: add Skynode upload scripts (#21842) 2023-08-21 18:16:37 +02:00
Daniel Agar 61bfa4fdc5 gitmodules update NuttX branch name 2023-08-15 21:15:48 -04:00
David Sidrane 3c94a447d6 NuttX with NXP Backports & DEBUGASSERT & Soket CAN fix
This is the same jump off point as main and release/1.14
  with several NXP arch backports, 2 Commit fixing bad DEBUGASSERT
  logic and a  Soket Can change.
2023-08-15 21:15:48 -04:00
Christian Rauch 44805b9e62 skip SSH key check for simpler builds in the Docker container 2023-08-14 10:45:16 -04:00
Christian Rauch c5fc5c83d2 pca9685_pwm_out: add parameter PCA9685_RATE to set update frequency 2023-08-08 12:49:21 -04:00
Christian Rauch ac1a157740 remove unused debug.h 2023-08-08 12:49:21 -04:00
Christian Rauch 8af893348a BMI0xx: remove unused board_dma_alloc.h 2023-08-08 12:49:21 -04:00
Christian Rauch 251e24bccb ADIS16497: replace NuttX specific up_udelay with HAL version px4_udelay 2023-08-08 12:49:21 -04:00
Christian Rauch fc80b09c84 enable common barometer, IMU and magnetometer 2023-08-08 12:49:21 -04:00
Daniel Agar 5359fe59e5 Jenkinsfile-compile fix invalid boards 2023-07-24 10:59:44 -04:00
Daniel Agar 24603589d2 Jenkinsfile-compile board updates 2023-07-18 13:53:14 -04:00
Beat Küng 4b70105583 airframes/x500_v2: move motors from AUX to MAIN 2023-07-18 11:12:20 -04:00
bresch 61036599db mag_cal: fix mag bias estimate to mag cal
- since last_us is set to 0 every time the bias is not observable, the
  total time was also reset -> needed 30 consecutive seconds in mag 3D
  to be declared "stable"
- after landing, the mag_aligned_in_flight flag is reset. Using this for
  bias validity makes it invalid before we have a chance to save it to
  the calibration.
2023-07-18 07:38:47 -07:00
bresch eb23779c57 ekf2 - preflt checks: scale flow innovation checks
Opt flow raw innovations can be really large on ground due to the small
distance to the ground (vel = flow / dist). To make the pre-flight check
more meaningful, scale it with the current distance.
2023-07-17 11:13:43 -04:00
bresch a07b8c08ab ekf2: report dist bottom also when using flow for terrain
Terrain height can be estimated using a range finder and/or optical flow
2023-07-17 11:13:43 -04:00
alexklimaj 36ec1fa811 Add EKF2_OF_QMIN_GND to handle 0 optical flow quality when on ground 2023-07-17 11:13:43 -04:00
alexklimaj 694501b782 Apply code review changes from @dagar 2023-07-17 11:13:43 -04:00
Eric Katzfey 7dd8e3f614 Removed the huge HAGL fuse timeout increase 2023-07-17 11:13:43 -04:00
Eric Katzfey fe335344e7 Cleaned up some comments and debug code 2023-07-17 11:13:43 -04:00
mjturi-mai 343c7fcd52 actual fixes for velocity estimate errors and bad rng fusion 2023-07-17 11:13:43 -04:00
Loic Fernau 66df5c1bd1 drivers: rework NXP UWB driver (#21124)
* UWB driver rework that uses 2 UWB MKBoards - 1 as Controller (Initiator), one as Controllee (Anchor)

Co-authored-by: NXPBrianna <108274268+NXPBrianna@users.noreply.github.com>
2023-07-12 11:49:40 -04:00
Ramon Roche 090f929659 drivers/barometer/invensense/icp201xx: increase delay after configuration (#21765)
- fixes wrong altitude reporting
2023-07-11 20:20:13 +02:00
alexklimaj 89b238f094 Revert "rover_pos_control: thrust normalization for joystick input (#20885)"
This reverts commit 22f7d913bd.
2023-07-11 08:26:09 -07:00
Matthias Grob ecd1e9f730 rc_update: fix on-off-switch with negative threshold values 2023-07-11 15:59:19 +02:00
Junwoo Hwang cca59843cc
netman: fix line too long (#21829)
Signed-off-by: Julian Oes <julian@oes.ch>
Co-authored-by: Julian Oes <julian@oes.ch>
2023-07-11 00:07:43 +02:00
Matthias Grob 1806a7cec8 drv_pwm_output: remove unused PWM_ defines 2023-07-10 19:00:52 +02:00
Matthias Grob 856b2e6178 UUV: stop motors when commanding zero speed 2023-07-10 19:00:52 +02:00
Matthias Grob e0e5b38c0e Boats: stop motors when commanding zero speed 2023-07-10 19:00:52 +02:00
Matthias Grob d0d113405a Rovers: stop motors when commanding zero speed 2023-07-10 19:00:52 +02:00
Matthias Grob 4ff03e4a06 TiltrotorVTOL: allow stopping front tilted motors in fast forward flight 2023-07-10 19:00:52 +02:00
Matthias Grob 8eb34ce8ce TailsitterVTOL: allow explicitly stop forward motor with zero thrust 2023-07-10 19:00:52 +02:00
Matthias Grob 62077908a3 StandardVTOL: explicitly stop forward motor with zero thrust 2023-07-10 19:00:52 +02:00
Matthias Grob cb2cc65eff FixedWing: explicitly stop forward motor with zero thrust
This allows PWM and all other output methods to configure
stopped, idling and full thrust points and use them consistently.
The fact that a fixed wing motor can be stopped when zero thrust
is demanded is explicit and could in principle even be disabled.
The mechanism is the same as for a standard VTOL stopping the
multicopter motors in the fixed wing flight phase.
2023-07-10 19:00:52 +02:00
Matthias Grob 4fc3f07cb1 ActuatorEffectiveness: add function to delectively stop motors with zero thrust 2023-07-10 19:00:52 +02:00
Matthias Grob 9b092d6d35 Set default minimum and maximum PWM for motors
This allows to consistently define:
Motor stopped - disarmed PWM
Motor idling - minimum PWM
Motor at full thrust - maximum PWM

Any allocation can then distinctly decide if
a motor should be running or not depending
on the context and also explicitly command that.
2023-07-10 19:00:52 +02:00
Vincent Poon 21fb22d581 Add ADC_ADS1115 Parameter to FMUv6x Default Build
Adding ADC_ADS1115 Parameter to FMUv6x Default Build to allow FMUv6X user to use ADS1115 with Analog Power Modules.
2023-07-07 13:42:00 +12:00
Julian Oes 3c1bcbdee6 fmu-v6x: build battery status
This is required to process data from the ADS1115 ADC and enables the
params BATx_I_CHANNEL and BATx_V_CHANNEL.

Testing is required whether this actually works on Pixhawk 6X though.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-07-07 13:42:00 +12:00
Julian Oes d9b1a695b5 ROMFS: auto try RGBLED is31fl3195
This is required to auto-start the is31fl3195 driver if connected.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-07-06 09:19:00 +12:00
Silvan Fuhrer 8838ebd77d Navigator: Loiter: always establish new Loiter with center at current pos
When switching into Hold mode establish a Loiter around current position,
even if we were before already loitering (eg in Mission mode).

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-07-04 17:03:14 +02:00
Silvan Fuhrer 7e0f0516a5 ROMFS: set default for VT_B_TRANS_DUR for all tailsitter configs to 5s
5s is a more reasobale time for tailsitters, which rely differently on this param
than other VTOL types. Tailsitters will ramp the pitch up withing this time,
while for other VTOLS types its only the max transitiont time.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-29 15:21:20 +02:00
Silvan Fuhrer 5b3d19944c ROMFS: tailsitter SITL config: improve tuning after model changes
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-29 15:21:20 +02:00
Silvan Fuhrer f2e706d7c4 ROMFS: quadtailsitter SITL config: improve tuning
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-29 15:21:20 +02:00
Julian Oes 5a5849d61a ROMFS: initial quadtailsitter tuning
This is now using the advanced lift drag plugin.

The important step was to enable airmode for yaw, otherwise yaw gets
saturated at low throttle and we can barely roll.

The other trick was to raise airspeed a little bit to avoid operating
too much at the lower end of throttle where control authority is low.

Signed-off-by: Julian Oes <julian@oes.ch>
2023-06-29 15:21:20 +02:00
JaeyoungLim 682190a21f Support quadtailsitter in SITL 2023-06-29 15:21:20 +02:00
Alex Klimaj e0a2e0b223
GPS RTCM selection fixes (#21666)
* uavcan rtcm set max num injections
* Subscribe to all instances of gps_inject_data and mirror uavcan rtcm pub mirror gps driver
* Minor logic refactor in gps and uavcan gps inject data
2023-06-20 11:24:06 -04:00
Silvan Fuhrer d9585bf3d3 FWRateController: use param find for VT_DIFTHR_EN as pure FW build doesn't have VTOL module built
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-19 11:00:23 +02:00
Matthias Grob 2374937388 FixedwingRateControl: rework VTOL differential thrust saturation
Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-19 11:00:23 +02:00
Matthias Grob ce8c4094a8 RateControl: allow setting individual saturation flags
This helps for more complicated cases where certain axes are controlled
through and get feedback from a different allocator.
2023-06-19 11:00:23 +02:00
Matthias Grob 11436f4109 esc_calibration: handle timeout wraps better
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
2023-06-16 15:48:20 +02:00
Matthias Grob db89bd5b5e esc_calibration: allow to calibrate ESCs without battery detection
Before this the ESC calibration aborts if battery detection doesn't work.
The problem is if the user still connects the battery as he gets instructed
and the calibration aborts then the ESCs are in calibration mode and
after abortion calibrate to the wrong value.

Also I realized there's no additional safety by aborting the calibration
if the battery cannot be detected during the timeout because a pixhawk
board without power module will report a battery status from the
ADC driverand in it that no battery is connected which is the best
it can do. In this situation the motors will still spin if the
ESCs are powered.
2023-06-16 15:48:20 +02:00
Matthias Grob ae678e8e2f esc_calibration: adjust timing to work with all tested ESCs
Some ESCs e.g. Gaui enter the menu relatively quickly if the
signal is high for too long. To solve that it's kept high shorter.
Also all tested ESCs detect the low signal within a shorter time
so no need to wait longer.
2023-06-16 15:48:20 +02:00
Matthias Grob 53bcb8789f esc_calibration: Improve readability and robustness
- Change timings for a more reliable calibration.
- Make sure there's an error message when battery measurement is not
available also when it gets disabled after system boot in the power
just above the calibration button.
- Safety check if measured electrical current goes up after issuing the
high calibration value for the case the user did not unplug power
and the detection either fails or is not enforced.
2023-06-16 15:48:20 +02:00
Matthias Grob afa56d21c5 mixer_module: consistent PWM/oneshot calibration range 2023-06-16 15:48:20 +02:00
Matthias Grob 8cb7a67819 actuator_test: condition order refactoring 2023-06-16 15:48:20 +02:00
Matthias Grob c89f0776f6 Unify MixingOutput constructor calls
to make them easy to search for and check the arguments.
2023-06-16 15:48:20 +02:00
Julian Oes b21e7e6c87 lights: Add LP5562 RGBLED driver
This adds support for the TI LP5562 RGB LED driver.

Things to note:
- The driver is initialized in simple PWM mode using its internal clock,
  for R,G,B, but not for W(hite).
- The chip doesn't have a WHO_AM_I or DEVICE_ID register to check.
  Instead we read the W_CURRENT register that we're generally not using
  and therefore doesn't get changed.
- The current is left at the default 17.5 mA but could be changed using
  the command line argument.

Datasheet:
https://www.ti.com/lit/ds/symlink/lp5562.pdf

Signed-off-by: Julian Oes <julian@oes.ch>
2023-06-13 13:51:59 +12:00
Matthias Grob ccb46a2152 PULL_REQUEST_TEMPLATE: fix typo 2023-06-06 17:44:32 +02:00
Matthias Grob f34fbdf0d3 rc_update: throttle trim centering fix for reverse channel
The entire logic did not work for the case when the throttle channel is
reversed because then QGC sets trim = max for that channel and
the result is only half the throttle range.
2023-06-06 17:44:32 +02:00
Junwoo Hwang 7cbf720d26
Geofence: Disable pre-emptive geofence predictor by default (#21657)
Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
2023-06-06 11:22:47 -04:00
Ramon Roche 29a3abb817 netman: update module description (#21664)
Co-authored-by: David Sidrane <David.Sidrane@Nscdg.com>
Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
2023-06-02 15:07:31 -04:00
Silvan Fuhrer 4e4ba40289 FW TECS: reduce default for FW_T_I_GAIN_THR to more appropriate 0.05
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-02 13:06:10 +02:00
Silvan Fuhrer d5cbf5df01 VTOL: params: add missing @decimal and @increment
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-02 13:06:10 +02:00
Silvan Fuhrer 0d7933beac Tiltrotor params: set default for VT_TILT_TRANS to 0.4
0.4 tilt is more reasobale to get nice transitions than
the previous 0.3.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-02 13:06:10 +02:00
Silvan Fuhrer 19029526d0 FWAttitudeController: params: increases parameter ranges
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-02 13:06:10 +02:00
Silvan Fuhrer b0712ef7a0 Commander: open up limits on TRIM_ROLL/PITCH/YAW to +/- 50%
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-02 13:06:10 +02:00
Silvan Fuhrer 71293b4943 FWRateController: fix @group, all should be in FW Rate Control group
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-02 13:06:10 +02:00
Silvan Fuhrer fb1491de33 FW Rate Controller: relax param ranges
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-02 13:06:10 +02:00
Silvan Fuhrer 487b9ca7ef Navigator: make sure to reset mission.item fields touched by set_vtol_transition_item
set_vtol_transition_item sets the params of the mission item directly
to values that make sense for NAV_CMD_DO_VTOL_TRANSITION, but don't
for other NAV_CMDs. So make sure that whenever we use it, we then in
the next step reset the touched mission_item fields.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-02 10:22:34 +02:00
Roman Bapst 5aa5fc2da5 Refactor uncommanded descend Quad-Chute (#21598)
* refactored uncommanded descend quadchute
- use fixed altitude error threshold
- compute error relative to higest altitude the vehicle has achieved
since it has flown below the altitude reference (setpoint)

* disabled altitude loss quadchute by default

* altitude loss quadchute: added protection against invalid local z


---------

Signed-off-by: RomanBapst <bapstroman@gmail.com>
2023-06-02 10:22:34 +02:00
Silvan Fuhrer 4b7da42a6e
FWPositionControl: navigateWaypoints: fix logic if already past waypoint and need to turn back (#21642)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2023-06-01 09:25:09 +02:00
261 changed files with 6609 additions and 2911 deletions

View File

@ -40,6 +40,8 @@ pipeline {
"ark_can-flow_default", "ark_can-flow_default",
"ark_can-gps_canbootloader", "ark_can-gps_canbootloader",
"ark_can-gps_default", "ark_can-gps_default",
"ark_cannode_canbootloader",
"ark_cannode_default",
"ark_can-rtk-gps_canbootloader", "ark_can-rtk-gps_canbootloader",
"ark_can-rtk-gps_default", "ark_can-rtk-gps_default",
"ark_fmu-v6x_bootloader", "ark_fmu-v6x_bootloader",
@ -53,8 +55,10 @@ pipeline {
"cuav_nora_default", "cuav_nora_default",
"cuav_x7pro_default", "cuav_x7pro_default",
"cubepilot_cubeorange_default", "cubepilot_cubeorange_default",
"cubepilot_cubeorangeplus_default",
"cubepilot_cubeyellow_default", "cubepilot_cubeyellow_default",
"diatone_mamba-f405-mk2_default", "diatone_mamba-f405-mk2_default",
"flywoo_gn-f405_default",
"freefly_can-rtk-gps_canbootloader", "freefly_can-rtk-gps_canbootloader",
"freefly_can-rtk-gps_default", "freefly_can-rtk-gps_default",
"holybro_can-gps-v1_canbootloader", "holybro_can-gps-v1_canbootloader",
@ -72,7 +76,7 @@ pipeline {
"matek_h743_default", "matek_h743_default",
"modalai_fc-v1_default", "modalai_fc-v1_default",
"modalai_fc-v2_default", "modalai_fc-v2_default",
"modalai_voxl2-io_default", "mro_ctrl-zero-classic_default",
"mro_ctrl-zero-f7_default", "mro_ctrl-zero-f7_default",
"mro_ctrl-zero-f7-oem_default", "mro_ctrl-zero-f7-oem_default",
"mro_ctrl-zero-h7-oem_default", "mro_ctrl-zero-h7-oem_default",
@ -85,6 +89,7 @@ pipeline {
"nxp_fmuk66-v3_default", "nxp_fmuk66-v3_default",
"nxp_fmuk66-v3_socketcan", "nxp_fmuk66-v3_socketcan",
"nxp_fmurt1062-v1_default", "nxp_fmurt1062-v1_default",
"nxp_mr-canhubk3_default",
"nxp_ucans32k146_canbootloader", "nxp_ucans32k146_canbootloader",
"nxp_ucans32k146_default", "nxp_ucans32k146_default",
"omnibus_f4sd_default", "omnibus_f4sd_default",

View File

@ -23,7 +23,7 @@ For release notes:
``` ```
Feature/Bugfix XYZ Feature/Bugfix XYZ
New parameter: XYZ_Z New parameter: XYZ_Z
Documentation: Need to clarfiy page ... / done, read docs.px4.io/... Documentation: Need to clarify page ... / done, read docs.px4.io/...
``` ```
### Alternatives ### Alternatives

2
.gitmodules vendored
View File

@ -21,7 +21,7 @@
[submodule "platforms/nuttx/NuttX/nuttx"] [submodule "platforms/nuttx/NuttX/nuttx"]
path = platforms/nuttx/NuttX/nuttx path = platforms/nuttx/NuttX/nuttx
url = https://github.com/PX4/NuttX.git url = https://github.com/PX4/NuttX.git
branch = px4_firmware_nuttx-10.3.0+ branch = px4_firmware_nuttx-10.3.0+-v1.14
[submodule "platforms/nuttx/NuttX/apps"] [submodule "platforms/nuttx/NuttX/apps"]
path = platforms/nuttx/NuttX/apps path = platforms/nuttx/NuttX/apps
url = https://github.com/PX4/NuttX-apps.git url = https://github.com/PX4/NuttX-apps.git

View File

@ -17,6 +17,7 @@ param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1 param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1 param set-default SENS_EN_MAGSIM 1
param set-default VT_B_TRANS_DUR 5
param set-default VT_ELEV_MC_LOCK 0 param set-default VT_ELEV_MC_LOCK 0
param set-default VT_TYPE 0 param set-default VT_TYPE 0
param set-default VT_FW_DIFTHR_EN 1 param set-default VT_FW_DIFTHR_EN 1

View File

@ -7,6 +7,7 @@
param set-default FW_LAUN_DETCN_ON 1 param set-default FW_LAUN_DETCN_ON 1
param set-default FW_THR_IDLE 0.1 # needs to be running before throw as that's how gazebo detects arming param set-default FW_THR_IDLE 0.1 # needs to be running before throw as that's how gazebo detects arming
param set-default FW_LAUN_AC_THLD 10
param set-default FW_LND_ANG 8 param set-default FW_LND_ANG 8

View File

@ -48,35 +48,32 @@ param set-default PWM_MAIN_REV 96 # invert both elevons
param set-default EKF2_MULTI_IMU 0 param set-default EKF2_MULTI_IMU 0
param set-default SENS_IMU_MODE 1 param set-default SENS_IMU_MODE 1
param set-default NPFG_PERIOD 12 param set-default FW_P_TC 0.6
param set-default FW_PR_I 0.2
param set-default FW_PR_P 0.2 param set-default FW_PR_FF 0.1
param set-default FW_PSP_OFF 2 param set-default FW_PSP_OFF 2
param set-default FW_P_LIM_MIN -15 param set-default FW_RR_FF 0.1
param set-default FW_RR_P 0.2 param set-default FW_RR_I 0.2
param set-default FW_THR_TRIM 0.33 param set-default FW_RR_P 0.3
param set-default FW_THR_MAX 0.6 param set-default FW_THR_TRIM 0.35
param set-default FW_THR_MAX 0.8
param set-default FW_THR_MIN 0.05 param set-default FW_THR_MIN 0.05
param set-default FW_T_ALT_TC 2 param set-default FW_T_CLMB_MAX 6
param set-default FW_T_CLMB_MAX 8 param set-default FW_T_HRATE_FF 0.5
param set-default FW_T_SINK_MAX 2.7 param set-default FW_T_SINK_MAX 3
param set-default FW_T_SINK_MIN 2.2 param set-default FW_T_SINK_MIN 1.6
param set-default FW_T_TAS_TC 2
param set-default MC_AIRMODE 1 param set-default MC_AIRMODE 1
param set-default MC_ROLL_P 3
param set-default MC_PITCH_P 3
param set-default MC_ROLLRATE_P 0.3 param set-default MC_ROLLRATE_P 0.3
param set-default MC_PITCHRATE_P 0.3
param set-default MPC_XY_P 0.8 param set-default VT_ARSP_TRANS 10
param set-default MPC_XY_VEL_P_ACC 3 param set-default VT_B_TRANS_DUR 5
param set-default MPC_XY_VEL_I_ACC 4
param set-default MPC_XY_VEL_D_ACC 0.1
param set-default NAV_ACC_RAD 5
param set-default VT_FW_DIFTHR_EN 1 param set-default VT_FW_DIFTHR_EN 1
param set-default VT_FW_DIFTHR_S_Y 0.5 param set-default VT_FW_DIFTHR_S_Y 1
param set-default VT_F_TRANS_DUR 1.5 param set-default VT_F_TRANS_DUR 1.5
param set-default VT_F_TRANS_THR 0.7
param set-default VT_TYPE 0 param set-default VT_TYPE 0
param set-default WV_EN 0 param set-default WV_EN 0

View File

@ -0,0 +1,74 @@
#!/bin/sh
#
# @name Quadrotor + Tailsitter
#
# @type VTOL Quad Tailsitter
#
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 20
param set-default CA_AIRFRAME 4
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.15
param set-default CA_ROTOR0_PY 0.23
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -0.15
param set-default CA_ROTOR1_PY -0.23
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.15
param set-default CA_ROTOR2_PY -0.23
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.15
param set-default CA_ROTOR3_PY 0.23
param set-default CA_ROTOR3_KM -0.05
param set-default CA_SV_CS_COUNT 0
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_FUNC5 0
parm set-default FD_FAIL_R 70
param set-default FW_P_TC 0.6
param set-default FW_PR_I 0.3
param set-default FW_PR_P 0.5
param set-default FW_PSP_OFF 2
param set-default FW_RR_FF 0.1
param set-default FW_RR_I 0.1
param set-default FW_RR_P 0.2
param set-default FW_YR_FF 0 # make yaw rate controller very weak, only keep default P
param set-default FW_YR_I 0
param set-default FW_THR_TRIM 0.35
param set-default FW_THR_MAX 0.8
param set-default FW_THR_MIN 0.05
param set-default FW_T_CLMB_MAX 6
param set-default FW_T_HRATE_FF 0.5
param set-default FW_T_SINK_MAX 3
param set-default FW_T_SINK_MIN 1.6
param set-default FW_AIRSPD_STALL 10
param set-default FW_AIRSPD_MIN 14
param set-default FW_AIRSPD_TRIM 18
param set-default FW_AIRSPD_MAX 22
param set-default MC_AIRMODE 2
param set-default MAN_ARM_GESTURE 0 # required for yaw airmode
param set-default MC_ROLL_P 3
param set-default MC_PITCH_P 3
param set-default MC_ROLLRATE_P 0.3
param set-default MC_PITCHRATE_P 0.3
param set-default VT_ARSP_TRANS 15
param set-default VT_B_TRANS_DUR 5
param set-default VT_FW_DIFTHR_EN 7
param set-default VT_FW_DIFTHR_S_Y 1
param set-default VT_F_TRANS_DUR 1.5
param set-default VT_TYPE 0
param set-default WV_EN 0

View File

@ -60,6 +60,7 @@ px4_add_romfs_files(
1042_gazebo-classic_tiltrotor 1042_gazebo-classic_tiltrotor
1043_gazebo-classic_standard_vtol_drop 1043_gazebo-classic_standard_vtol_drop
1044_gazebo-classic_plane_lidar 1044_gazebo-classic_plane_lidar
1045_gazebo-classic_quadtailsitter
1060_gazebo-classic_rover 1060_gazebo-classic_rover
1061_gazebo-classic_r1_rover 1061_gazebo-classic_r1_rover
1062_flightgear_tf-r1 1062_flightgear_tf-r1

View File

@ -20,6 +20,7 @@
param set-default EKF2_FUSE_BETA 0 # side slip fusion is currently not supported for tailsitters param set-default EKF2_FUSE_BETA 0 # side slip fusion is currently not supported for tailsitters
param set UAVCAN_ENABLE 0 param set UAVCAN_ENABLE 0
param set-default VT_B_TRANS_DUR 5
param set-default VT_ELEV_MC_LOCK 0 param set-default VT_ELEV_MC_LOCK 0
param set-default VT_MOT_COUNT 2 param set-default VT_MOT_COUNT 2
param set-default VT_TYPE 0 param set-default VT_TYPE 0

View File

@ -31,3 +31,4 @@ param set-default CA_SV_CS1_TYPE 6
param set-default MAV_TYPE 19 param set-default MAV_TYPE 19
param set-default VT_TYPE 0 param set-default VT_TYPE 0
param set-default VT_ELEV_MC_LOCK 0 param set-default VT_ELEV_MC_LOCK 0
param set-default VT_B_TRANS_DUR 5

View File

@ -34,9 +34,7 @@ param set-default CA_ROTOR3_PX -0.25
param set-default CA_ROTOR3_PY 0.25 param set-default CA_ROTOR3_PY 0.25
param set-default CA_ROTOR3_KM -0.05 param set-default CA_ROTOR3_KM -0.05
param set-default PWM_AUX_FUNC1 101 param set-default PWM_MAIN_FUNC1 101
param set-default PWM_AUX_FUNC2 102 param set-default PWM_MAIN_FUNC2 102
param set-default PWM_AUX_FUNC3 103 param set-default PWM_MAIN_FUNC3 103
param set-default PWM_AUX_FUNC4 104 param set-default PWM_MAIN_FUNC4 104
param set-default PWM_AUX_TIM0 -4

View File

@ -162,7 +162,7 @@ else
param select-backup $PARAM_BACKUP_FILE param select-backup $PARAM_BACKUP_FILE
fi fi
if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X ARK_FMU_V6X if mft query -q -k MFT -s MFT_ETHERNET -v 1
then then
netman update -i eth0 netman update -i eth0
fi fi
@ -254,6 +254,8 @@ else
# #
rgbled start -X -q rgbled start -X -q
rgbled_ncp5623c start -X -q rgbled_ncp5623c start -X -q
rgbled_lp5562 start -X -q
rgbled_is31fl3195 start -X -q
# #
# Override parameters from user configuration file. # Override parameters from user configuration file.
@ -264,12 +266,9 @@ else
. $FCONFIG . $FCONFIG
fi fi
# if px4io supported
# Start IO for PWM output or RC input if enabled
#
if param compare -s SYS_USE_IO 1
then then
# Check if PX4IO present and update firmware if needed. # Check if PX4IO present and update firmware if needed.
if [ -f $IOFW ] if [ -f $IOFW ]
then then
if ! px4io checkcrc ${IOFW} if ! px4io checkcrc ${IOFW}
@ -291,12 +290,12 @@ else
tune_control stop tune_control stop
fi fi
fi fi
fi
if ! px4io start if ! px4io start
then then
echo "PX4IO start failed" echo "PX4IO start failed"
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
fi
fi fi
fi fi

View File

@ -0,0 +1,115 @@
#!/bin/bash
# Flash PX4 to a device running AuterionOS in the local network
if [ "$1" == "-h" ] || [ "$1" == "--help" ] || [ $# -lt 2 ]; then
echo "Usage: $0 -f <firmware.px4|.elf> [-c <configuration_dir>] -d <IP/Device> [-u <user>] [-p <ssh_port>] [--revert]"
exit 1
fi
ssh_port=22
ssh_user=root
while getopts ":f:c:d:p:u:r" opt; do
case ${opt} in
f )
if [ -n "$OPTARG" ]; then
firmware_file="$OPTARG"
else
echo "ERROR: -f requires a non-empty option argument."
exit 1
fi
;;
c )
if [ -f "$OPTARG/rc.autostart" ]; then
config_dir="$OPTARG"
else
echo "ERROR: -c configuration directory is empty or does not contain a valid rc.autostart"
exit 1
fi
;;
d )
if [ "$OPTARG" ]; then
device="$OPTARG"
else
echo "ERROR: -d requires a non-empty option argument."
exit 1
fi
;;
p )
if [[ "$OPTARG" =~ ^[0-9]+$ ]]; then
ssh_port="$OPTARG"
else
echo "ERROR: -p ssh_port must be a number."
exit 1
fi
;;
u )
if [ "$OPTARG" ]; then
ssh_user="$OPTARG"
else
echo "ERROR: -u requires a non-empty option argument."
exit 1
fi
;;
r )
revert=true
;;
esac
done
if [ -z "$device" ]; then
echo "Error: missing device"
exit 1
fi
target_dir=/shared_container_dir/fmu
target_file_name="update-dev.tar"
if [ "$revert" == true ]; then
# revert to the release version which was originally deployed
cmd="cp $target_dir/update.tar $target_dir/$target_file_name"
ssh -t -p $ssh_port $ssh_user@$device "$cmd"
else
# create custom update-dev.tar
tmp_dir="$(mktemp -d)"
config_path=""
firmware_path=""
if [ -d "$config_dir" ]; then
cp -r "$config_dir" "$tmp_dir/config"
config_path=config
fi
if [ -f "$firmware_file" ]; then
extension="${firmware_file##*.}"
cp "$firmware_file" "$tmp_dir/firmware.$extension"
if [ "$extension" == "elf" ]; then
# ensure the file is stripped to reduce file size
arm-none-eabi-strip "$tmp_dir/firmware.$extension"
fi
firmware_path="firmware.$extension"
fi
pushd "$tmp_dir" &>/dev/null
if [ -z $firmware_path ] && [ -z $config_path ]; then
exit 1
fi
tar_name="tar"
if [ -x "$(command -v gtar)" ]; then
# check if gnu-tar is installed on macOS and use that instead
tar_name="gtar"
fi
$tar_name -C "$tmp_dir" --sort=name --owner=root:0 --group=root:0 --mtime='2019-01-01 00:00:00' -cvf $target_file_name $firmware_path $config_path
# send it to the target to start flashing
scp -P $ssh_port "$target_file_name" $ssh_user@"$device":$target_dir
popd &>/dev/null
rm -rf "$tmp_dir"
fi
# grab status output for flashing progress
cmd="tail --follow=name $target_dir/update_status 2>/dev/null || true"
ssh -t -p $ssh_port $ssh_user@$device "$cmd"

View File

@ -0,0 +1,51 @@
#!/usr/bin/env bash
DIR="$(dirname $(readlink -f $0))"
DEFAULT_AUTOPILOT_HOST=10.41.1.1
DEFAULT_AUTOPILOT_PORT=33333
DEFAULT_AUTOPILOT_USER=auterion
for i in "$@"
do
case $i in
--file=*)
PX4_BINARY_FILE="${i#*=}"
;;
--default-ip=*)
DEFAULT_AUTOPILOT_HOST="${i#*=}"
;;
--default-port=*)
DEFAULT_AUTOPILOT_PORT="${i#*=}"
;;
--default-user=*)
DEFAULT_AUTOPILOT_USER="${i#*=}"
;;
--revert)
REVERT_AUTOPILOT_ARGUMENT=-r
;;
--wifi)
DEFAULT_AUTOPILOT_HOST=10.41.0.1
;;
*)
# unknown option
;;
esac
done
# allow these to be overridden
[ -z "$AUTOPILOT_HOST" ] && AUTOPILOT_HOST=$DEFAULT_AUTOPILOT_HOST
[ -z "$AUTOPILOT_PORT" ] && AUTOPILOT_PORT=$DEFAULT_AUTOPILOT_PORT
[ -z "$AUTOPILOT_USER" ] && AUTOPILOT_USER=$DEFAULT_AUTOPILOT_USER
ARGUMENTS=()
ARGUMENTS+=(-d "$AUTOPILOT_HOST")
ARGUMENTS+=(-p "$AUTOPILOT_PORT")
ARGUMENTS+=(-u "$AUTOPILOT_USER")
ARGUMENTS+=(${PX4_BINARY_FILE:+-f "$PX4_BINARY_FILE"})
ARGUMENTS+=($REVERT_AUTOPILOT_ARGUMENT)
echo "Flashing $AUTOPILOT_HOST ..."
"$DIR"/remote_update_fmu.sh "${ARGUMENTS[@]}"
exit 0

View File

@ -20,6 +20,7 @@ CONFIG_DRIVERS_HEATER=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y
CONFIG_COMMON_LIGHT=y CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y CONFIG_COMMON_OPTICAL_FLOW=y

View File

@ -17,17 +17,19 @@ param set-default SENS_EN_INA228 0
param set-default SENS_EN_INA226 1 param set-default SENS_EN_INA226 1
param set-default SENS_EN_THERMAL 1 param set-default SENS_EN_THERMAL 1
param set-default SENS_TEMP_ID 2818058
param set-default SENS_IMU_TEMP 10.0 param set-default SENS_IMU_TEMP 10.0
#param set-default SENS_IMU_TEMP_FF 0.0 #param set-default SENS_IMU_TEMP_FF 0.0
#param set-default SENS_IMU_TEMP_I 0.025 #param set-default SENS_IMU_TEMP_I 0.025
#param set-default SENS_IMU_TEMP_P 1.0 #param set-default SENS_IMU_TEMP_P 1.0
if ver hwtypecmp ARKV6X001000 ARKV6X001001 ARKV6X001002 ARKV6X001003 ARKV6X001004 ARKV6X001005 ARKV6X001006 ARKV6X001007 if ver hwtypecmp ARKV6X000
then then
param set-default SYS_USE_IO 0 param set-default SENS_TEMP_ID 2818058
else fi
param set-default SYS_USE_IO 1
if ver hwtypecmp ARKV6X001
then
param set-default SENS_TEMP_ID 3014666
fi fi
safety_button start safety_button start

View File

@ -4,7 +4,7 @@
#------------------------------------------------------------------------------ #------------------------------------------------------------------------------
set HAVE_PM2 yes set HAVE_PM2 yes
if ver hwtypecmp ARKV6X005000 ARKV6X005001 ARKV6X005002 ARKV6X005003 ARKV6X005004 if mft query -q -k MFT -s MFT_PM2 -v 0
then then
set HAVE_PM2 no set HAVE_PM2 no
fi fi
@ -47,14 +47,29 @@ then
fi fi
fi fi
# Internal SPI bus IIM42652 with SPIX measured frequency of 32.051kHz if ver hwtypecmp ARKV6X000
iim42652 -R 3 -s -b 1 -C 32051 start then
# Internal SPI bus IIM42652 with SPIX measured frequency of 32.051kHz
iim42652 -R 3 -s -b 1 -C 32051 start
# Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz # Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz
icm42688p -R 9 -s -b 2 -C 32051 start icm42688p -R 9 -s -b 2 -C 32051 start
# Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz # Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz
icm42688p -R 6 -s -b 3 -C 32051 start icm42688p -R 6 -s -b 3 -C 32051 start
fi
if ver hwtypecmp ARKV6X001
then
# Internal SPI bus IIM42653 with SPIX measured frequency of 32.051kHz
iim42653 -R 3 -s -b 1 -C 32051 start
# Internal SPI bus IIM42653 with SPIX measured frequency of 32.051kHz
iim42653 -R 9 -s -b 2 -C 32051 start
# Internal SPI bus IIM42653 with SPIX measured frequency of 32.051kHz
iim42653 -R 6 -s -b 3 -C 32051 start
fi
# Internal magnetometer on I2C # Internal magnetometer on I2C
bmm150 -I start bmm150 -I start

View File

@ -55,7 +55,6 @@ else()
init.c init.c
led.c led.c
mtd.cpp mtd.cpp
manifest.c
sdio.c sdio.c
spi.cpp spi.cpp
spix_sync.c spix_sync.c

View File

@ -1,6 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2016-2022 PX4 Development Team. All rights reserved. * Copyright (c) 2016-2024 PX4 Development Team. All rights reserved.
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -204,30 +204,17 @@
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) #define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* HW Version and Revision drive signals Default to 1 to detect */ /* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING #define BOARD_HAS_HW_SPLIT_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_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_REV_SENSE /* PH4 */ GPIO_ADC3_INP15
#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14 #define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14
#define HW_INFO_INIT_PREFIX "ARKV6X" #define HW_INFO_INIT_PREFIX "ARKV6X"
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2 // Rev 0 and Rev 3,4 Sensor sets #define BOARD_NUM_SPI_CFG_HW_VERSIONS 2
// Base/FMUM // Base/FMUM
#define ARKV6X00 HW_VER_REV(0x0,0x0) // ARKV6X, Rev 0 #define ARKV6X_0 HW_FMUM_ID(0x0) // ARKV6X, Sensor Set Rev 0
#define ARKV6X01 HW_VER_REV(0x0,0x1) // ARKV6X, BMI388 I2C2 Rev 1 #define ARKV6X_1 HW_FMUM_ID(0x1) // ARKV6X, Sensor Set Rev 1
#define ARKV6X03 HW_VER_REV(0x0,0x3) // ARKV6X, Sensor Set Rev 3
#define ARKV6X04 HW_VER_REV(0x0,0x4) // ARKV6X, Sensor Set Rev 4
#define ARKV6X10 HW_VER_REV(0x1,0x0) // NO PX4IO, Rev 0
#define ARKV6X13 HW_VER_REV(0x1,0x3) // NO PX4IO, Sensor Set Rev 3
#define ARKV6X14 HW_VER_REV(0x1,0x4) // NO PX4IO, Sensor Set Rev 4
//#define ARKV6X40 HW_VER_REV(0x4,0x0) // ARKV6X, HB CM4 base Rev 0 // never shipped
//#define ARKV6X41 HW_VER_REV(0x4,0x1) // ARKV6X, BMI388 I2C2 HB CM4 base Rev 1 // never shipped
#define ARKV6X43 HW_VER_REV(0x4,0x3) // ARKV6X, Sensor Set HB CM4 base Rev 3
#define ARKV6X44 HW_VER_REV(0x4,0x4) // ARKV6X, Sensor Set HB CM4 base Rev 4
#define ARKV6X50 HW_VER_REV(0x5,0x0) // ARKV6X, ARKV6X Rev 0 with HB Mini Rev 5
//#define ARKV6X51 HW_VER_REV(0x5,0x1) // ARKV6X, BMI388 I2C2 HB Mini Rev 1 // never shipped
#define ARKV6X53 HW_VER_REV(0x5,0x3) // ARKV6X, Sensor Set HB Mini Rev 3
#define ARKV6X54 HW_VER_REV(0x5,0x4) // ARKV6X, Sensor Set HB Mini Rev 4
#define UAVCAN_NUM_IFACES_RUNTIME 1 #define UAVCAN_NUM_IFACES_RUNTIME 1
@ -252,7 +239,6 @@
/* PWM /* PWM
*/ */
#define DIRECT_PWM_OUTPUT_CHANNELS 8 #define DIRECT_PWM_OUTPUT_CHANNELS 8
#define BOARD_PWM_FREQ 1024000
#define GPIO_FMU_CH1 /* PI0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTI|GPIO_PIN0) #define GPIO_FMU_CH1 /* PI0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTI|GPIO_PIN0)
#define GPIO_FMU_CH2 /* PH12 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN12) #define GPIO_FMU_CH2 /* PH12 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN12)

View File

@ -1,223 +0,0 @@
/****************************************************************************
*
* 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_v0640[] = {
{
// 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_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
{ARKV6X00, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)},
{ARKV6X01, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2
{ARKV6X03, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 3
//{ARKV6X40, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // HB CM4 base // never shipped
//{ARKV6X41, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // BMP388 moved to I2C2 HB CM4 base // never shipped
{ARKV6X43, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // BMP388 moved to I2C2, HB CM4 base Sensor Set 3
{ARKV6X44, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // BMP388 moved to I2C2, HB CM4 base Sensor Set 4
{ARKV6X50, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // ARKV6X Rev 0 with HB Mini Rev 5
//{ARKV6X51, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2 HB Mini // never shipped
{ARKV6X53, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 3
{ARKV6X54, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 4
{ARKV6X10, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO
{ARKV6X13, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO BMP388 moved to I2C2, Sensor Set 3
{ARKV6X04, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 4
{ARKV6X14, 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() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
if (mft_lists[i].hw_ver_rev == ver_rev) {
boards_manifest = &mft_lists[i];
break;
}
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
px4_hw_mft_item rv = &device_unsupported;
if (boards_manifest != px4_hw_mft_list_uninitialized &&
id < boards_manifest->entries) {
rv = &boards_manifest->mft[id];
}
return rv;
}

View File

@ -1,6 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (C) 2022 PX4 Development Team. All rights reserved. * Copyright (C) 2024 PX4 Development Team. All rights reserved.
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -31,6 +31,9 @@
* *
****************************************************************************/ ****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <nuttx/spi/spi.h> #include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h> #include <px4_platform_common/px4_manifest.h>
// KiB BS nB // KiB BS nB
@ -92,10 +95,16 @@ static const px4_mft_entry_s mtd_mft = {
.pmft = (void *) &board_mtd_config, .pmft = (void *) &board_mtd_config,
}; };
static const px4_mft_entry_s mft_mft = {
.type = MFT,
.pmft = (void *) system_query_manifest,
};
static const px4_mft_s mft = { static const px4_mft_s mft = {
.nmft = 1, .nmft = 2,
.mfts = { .mfts = {
&mtd_mft &mtd_mft,
&mft_mft,
} }
}; };

View File

@ -1,6 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (C) 2022 PX4 Development Team. All rights reserved. * Copyright (C) 2024 PX4 Development Team. All rights reserved.
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -36,7 +36,7 @@
#include <nuttx/spi/spi.h> #include <nuttx/spi/spi.h>
constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = { constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = {
initSPIHWVersion(ARKV6X00, { initSPIFmumID(ARKV6X_0, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
@ -59,15 +59,15 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
}), }),
}), }),
initSPIHWVersion(ARKV6X01, { // Placeholder initSPIFmumID(ARKV6X_1, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
initSPIBus(SPI::Bus::SPI2, { initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}),
}, {GPIO::PortF, GPIO::Pin4}), }, {GPIO::PortF, GPIO::Pin4}),
initSPIBus(SPI::Bus::SPI3, { initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}),
}, {GPIO::PortE, GPIO::Pin7}), }, {GPIO::PortE, GPIO::Pin7}),
// initSPIBus(SPI::Bus::SPI4, { // initSPIBus(SPI::Bus::SPI4, {
// // no devices // // no devices

View File

@ -82,9 +82,7 @@
#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET) #define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET) #define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET)
#if !defined(BOARD_PWM_FREQ) #define BOARD_SPIX_SYNC_PWM_FREQ 1024000
#define BOARD_PWM_FREQ 1000000
#endif
unsigned unsigned
spix_sync_timer_get_period(unsigned timer) spix_sync_timer_get_period(unsigned timer)
@ -129,11 +127,11 @@ static void spix_sync_timer_init_timer(unsigned timer, unsigned rate)
* Otherwise, other frequencies are attainable by adjusting .clock_freq accordingly. * Otherwise, other frequencies are attainable by adjusting .clock_freq accordingly.
*/ */
rPSC(timer) = (spix_sync_timers[timer].clock_freq / BOARD_PWM_FREQ) - 1; rPSC(timer) = (spix_sync_timers[timer].clock_freq / BOARD_SPIX_SYNC_PWM_FREQ) - 1;
/* configure the timer to update at the desired rate */ /* configure the timer to update at the desired rate */
rARR(timer) = (BOARD_PWM_FREQ / rate) - 1; rARR(timer) = (BOARD_SPIX_SYNC_PWM_FREQ / rate) - 1;
/* generate an update event; reloads the counter and all registers */ /* generate an update event; reloads the counter and all registers */
rEGR(timer) = GTIM_EGR_UG; rEGR(timer) = GTIM_EGR_UG;

View File

@ -140,15 +140,7 @@
#define PX4_PWM_ALTERNATE_RANGES #define PX4_PWM_ALTERNATE_RANGES
#define PWM_LOWEST_MIN 0 #define PWM_LOWEST_MIN 0
#define PWM_MOTOR_OFF 0
#define PWM_SERVO_STOP 0
#define PWM_DEFAULT_MIN 20
#define PWM_HIGHEST_MIN 0
#define PWM_HIGHEST_MAX 255 #define PWM_HIGHEST_MAX 255
#define PWM_DEFAULT_MAX 255
#define PWM_LOWEST_MAX 255
#define PWM_DEFAULT_TRIM 1500
/* High-resolution timer */ /* High-resolution timer */
#define HRT_TIMER 8 /* use timer8 for the HRT */ #define HRT_TIMER 8 /* use timer8 for the HRT */

View File

@ -141,15 +141,7 @@
#define PX4_PWM_ALTERNATE_RANGES #define PX4_PWM_ALTERNATE_RANGES
#define PWM_LOWEST_MIN 0 #define PWM_LOWEST_MIN 0
#define PWM_MOTOR_OFF 0
#define PWM_SERVO_STOP 0
#define PWM_DEFAULT_MIN 20
#define PWM_HIGHEST_MIN 0
#define PWM_HIGHEST_MAX 255 #define PWM_HIGHEST_MAX 255
#define PWM_DEFAULT_MAX 255
#define PWM_LOWEST_MAX 255
#define PWM_DEFAULT_TRIM 1500
/* High-resolution timer */ /* High-resolution timer */
#define HRT_TIMER 8 /* use timer8 for the HRT */ #define HRT_TIMER 8 /* use timer8 for the HRT */

View File

@ -14,6 +14,4 @@ param set-default SENS_EN_THERMAL 0
param set-default -s SENS_TEMP_ID 2621474 param set-default -s SENS_TEMP_ID 2621474
param set-default SYS_USE_IO 1
set IOFW "/etc/extras/cubepilot_io-v2_default.bin" set IOFW "/etc/extras/cubepilot_io-v2_default.bin"

View File

@ -14,6 +14,4 @@ param set-default SENS_EN_THERMAL 0
param set-default -s SENS_TEMP_ID 2621474 param set-default -s SENS_TEMP_ID 2621474
param set-default SYS_USE_IO 1
set IOFW "/etc/extras/cubepilot_io-v2_default.bin" set IOFW "/etc/extras/cubepilot_io-v2_default.bin"

View File

@ -8,16 +8,22 @@ board_adc start
# 1. Isolated {ICM42688p, ICM20948(with mag)}, body-fixed {ICM20649} # 1. Isolated {ICM42688p, ICM20948(with mag)}, body-fixed {ICM20649}
# 2. Isolated {ICM42688p, ICM42688p}, body-fixed {ICM20649, ICM45686, AK09918} # 2. Isolated {ICM42688p, ICM42688p}, body-fixed {ICM20649, ICM45686, AK09918}
# 3. Isolated {ICM42688p, ICM42688p}, body-fixed {ICM45686, AK09918} # 3. Isolated {ICM42688p, ICM42688p}, body-fixed {ICM45686, AK09918}
# 4. Isolated {ICM45686, ICM45686}, body-fixed {ICM45686, AK09918}
# SPI4 is isolated, SPI1 is body-fixed # SPI4 is isolated, SPI1 is body-fixed
# SPI4, isolated # SPI4, isolated
ms5611 -s -b 4 start ms5611 -s -b 4 start
icm42688p -s -b 4 -R 10 start -c 15 if icm42688p -s -b 4 -R 10 -q start -c 15
if ! icm20948 -s -b 4 -R 10 -M -q start
then then
icm42688p -s -b 4 -R 6 start -c 13 if ! icm20948 -s -b 4 -R 10 -M -q start
then
icm42688p -s -b 4 -R 6 start -c 13
fi
else
icm45686 -s -b 4 -R 10 start -c 15
icm45686 -s -b 4 -R 6 start -c 13
fi fi
# SPI1, body-fixed # SPI1, body-fixed

View File

@ -49,7 +49,9 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI4, { initSPIBus(SPI::Bus::SPI4, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20948, SPI::CS{GPIO::PortE, GPIO::Pin4}), // MPU_EXT_CS initSPIDevice(DRV_IMU_DEVTYPE_ICM20948, SPI::CS{GPIO::PortE, GPIO::Pin4}), // MPU_EXT_CS
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortC, GPIO::Pin15}), // ACCEL_EXT_CS initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortC, GPIO::Pin15}), // ACCEL_EXT_CS
initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortC, GPIO::Pin15}), // ACCEL_EXT_CS
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortC, GPIO::Pin13}), // GYRO_EXT_CS initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortC, GPIO::Pin13}), // GYRO_EXT_CS
initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortC, GPIO::Pin13}), // GYRO_EXT_CS
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortC, GPIO::Pin14}), // BARO_EXT_CS initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortC, GPIO::Pin14}), // BARO_EXT_CS
}), }),
}; };

View File

@ -13,6 +13,4 @@ param set-default BAT2_A_PER_V 17
# Disable IMU thermal control # Disable IMU thermal control
param set-default SENS_EN_THERMAL 0 param set-default SENS_EN_THERMAL 0
param set-default SYS_USE_IO 1
set IOFW "/etc/extras/cubepilot_io-v2_default.bin" set IOFW "/etc/extras/cubepilot_io-v2_default.bin"

View File

@ -11,5 +11,3 @@ param set-default BAT2_A_PER_V 36.367515152
# Enable IMU thermal control # Enable IMU thermal control
param set-default SENS_EN_THERMAL 1 param set-default SENS_EN_THERMAL 1
param set-default SYS_USE_IO 1

View File

@ -33,6 +33,12 @@ CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y CONFIG_MODULES_EKF2=y
# CONFIG_EKF2_AUXVEL is not set
# CONFIG_EKF2_BARO_COMPENSATION is not set
# CONFIG_EKF2_DRAG_FUSION is not set
# CONFIG_EKF2_EXTERNAL_VISION is not set
# CONFIG_EKF2_GNSS_YAW is not set
# CONFIG_EKF2_SIDESLIP is not set
CONFIG_MODULES_ESC_BATTERY=y CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y

View File

@ -22,13 +22,10 @@ param set-default CBRK_SUPPLY_CHK 894281
# Select the Generic 250 Racer by default # Select the Generic 250 Racer by default
param set-default SYS_AUTOSTART 4050 param set-default SYS_AUTOSTART 4050
# use the Q attitude estimator, it works w/o mag or GPS. # use EKF2 without mag
param set-default SYS_MC_EST_GROUP 3
param set-default ATT_ACC_COMP 0
param set-default ATT_W_ACC 0.4000
param set-default ATT_W_GYRO_BIAS 0.0000
param set-default SYS_HAS_MAG 0 param set-default SYS_HAS_MAG 0
# and enable gravity fusion
param set-default EKF2_IMU_CONTROL 7
# the startup tune is not great on a binary output buzzer, so disable it # the startup tune is not great on a binary output buzzer, so disable it
param set-default CBRK_BUZZER 782090 param set-default CBRK_BUZZER 782090

View File

@ -32,6 +32,12 @@ CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y CONFIG_MODULES_EKF2=y
# CONFIG_EKF2_AUXVEL is not set
# CONFIG_EKF2_BARO_COMPENSATION is not set
# CONFIG_EKF2_DRAG_FUSION is not set
# CONFIG_EKF2_EXTERNAL_VISION is not set
# CONFIG_EKF2_GNSS_YAW is not set
# CONFIG_EKF2_SIDESLIP is not set
CONFIG_MODULES_ESC_BATTERY=y CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y

View File

@ -33,6 +33,12 @@ CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y CONFIG_MODULES_EKF2=y
# CONFIG_EKF2_AUXVEL is not set
# CONFIG_EKF2_BARO_COMPENSATION is not set
# CONFIG_EKF2_DRAG_FUSION is not set
# CONFIG_EKF2_EXTERNAL_VISION is not set
# CONFIG_EKF2_GNSS_YAW is not set
# CONFIG_EKF2_SIDESLIP is not set
CONFIG_MODULES_ESC_BATTERY=y CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y

View File

@ -9,7 +9,5 @@ param set-default BAT2_V_DIV 18.1
param set-default BAT1_A_PER_V 36.367515152 param set-default BAT1_A_PER_V 36.367515152
param set-default BAT2_A_PER_V 36.367515152 param set-default BAT2_A_PER_V 36.367515152
param set-default SYS_USE_IO 1
rgbled_pwm start rgbled_pwm start
safety_button start safety_button start

View File

@ -5,5 +5,3 @@
param set-default BAT1_V_DIV 10.177939394 param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303 param set-default BAT1_A_PER_V 15.391030303
param set-default SYS_USE_IO 1

View File

@ -5,5 +5,3 @@
param set-default BAT1_V_DIV 10.177939394 param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303 param set-default BAT1_A_PER_V 15.391030303
param set-default SYS_USE_IO 1

View File

@ -19,6 +19,7 @@ CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IRLOCK=y CONFIG_DRIVERS_IRLOCK=y
CONFIG_DRIVERS_UWB_UWB_SR150=y
CONFIG_COMMON_LIGHT=y CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y CONFIG_COMMON_MAGNETOMETER=y

View File

@ -22,7 +22,7 @@ CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_DRIVERS_TONE_ALARM=y CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_COMMON_UWB=y CONFIG_DRIVERS_UWB_UWB_SR150=y
CONFIG_MODULES_BATTERY_STATUS=y CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y CONFIG_MODULES_COMMANDER=y

View File

@ -1,20 +1,25 @@
# CONFIG_BOARD_ROMFSROOT is not set # CONFIG_BOARD_ROMFSROOT is not set
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1" CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS4"
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5" CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
CONFIG_BOARD_UAVCAN_INTERFACES=1 CONFIG_BOARD_UAVCAN_INTERFACES=1
CONFIG_COMMON_LIGHT=y CONFIG_COMMON_LIGHT=y
CONFIG_CYPHAL_BMS_SUBSCRIBER=y CONFIG_CYPHAL_BMS_SUBSCRIBER=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_CYPHAL=y CONFIG_DRIVERS_CYPHAL=y
CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IRLOCK=y CONFIG_DRIVERS_IRLOCK=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL=y CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL=y
CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_DRIVERS_UAVCAN=y CONFIG_DRIVERS_UAVCAN=y
CONFIG_EXAMPLES_FAKE_GPS=y CONFIG_EXAMPLES_FAKE_GPS=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_ESC_BATTERY=y CONFIG_MODULES_ESC_BATTERY=y

View File

@ -17,6 +17,17 @@ param set-default MAV_1_UDP_PRT 14550
param set-default SENS_EXT_I2C_PRB 0 param set-default SENS_EXT_I2C_PRB 0
param set-default CYPHAL_ENABLE 0 param set-default CYPHAL_ENABLE 0
if ver hwtypecmp MR-CANHUBK3-ADAP
then
param set-default GPS_1_CONFIG 202
param set-default RC_PORT_CONFIG 104
param set-default SENS_INT_BARO_EN 0
param set-default SYS_HAS_BARO 0
# MR-CANHUBK3-ADAP voltage divider
param set-default BAT1_V_DIV 13.158
safety_button start
fi
if param greater -s UAVCAN_ENABLE 0 if param greater -s UAVCAN_ENABLE 0
then then
ifup can0 ifup can0

View File

@ -2,22 +2,31 @@
# #
# NXP MR-CANHUBK3 specific board sensors init # NXP MR-CANHUBK3 specific board sensors init
#------------------------------------------------------------------------------ #------------------------------------------------------------------------------
if ver hwtypecmp MR-CANHUBK3-ADAP
then
icm42688p -c 2 -b 3 -R 0 -S -f 15000 start
# Internal magnetometer on I2c on ADAP
bmm150 -X -a 18 start
ist8310 -X -b 1 -R 10 start
# ADC for voltage input sensing
board_adc start
#board_adc start FIXME no ADC drivers # External SPI bus ICM20649
icm20649 -b 4 -S -R 10 start
#FMUv5Xbase board orientation # External SPI bus ICM42688p
icm42688p -c 1 -b 3 -R 10 -S -f 15000 start
else
bmm150 -X 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 2 -R 10 start
# Internal SPI bus ICM20649 # External SPI bus ICM20649
icm20649 -s -R 6 start icm20649 -b 4 -S -R 6 start
# Internal SPI bus ICM42688p # External SPI bus ICM42688p
icm42688p -R 6 -s start icm42688p -c 1 -b 3 -R 6 -S -f 15000 start
fi
# 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 2 -R 10 start
# External compass on GPS1/I2C1 (the 3rd external bus): Drotek RTK GPS with LIS3MDL Compass # External compass on GPS1/I2C1 (the 3rd external bus): Drotek RTK GPS with LIS3MDL Compass
lis3mdl -X -b 2 -R 2 start lis3mdl -X -b 2 -R 2 start
@ -25,5 +34,5 @@ lis3mdl -X -b 2 -R 2 start
# Disable startup of internal baros if param is set to false # Disable startup of internal baros if param is set to false
if param compare SENS_INT_BARO_EN 1 if param compare SENS_INT_BARO_EN 1
then then
bmp388 -I -a 0x77 start bmp388 -X -a 0x77 start
fi fi

View File

@ -152,6 +152,18 @@
#define PIN_LPUART1_RX (PIN_LPUART1_RX_3 | PIN_INPUT_PULLUP) /* PTC6 */ #define PIN_LPUART1_RX (PIN_LPUART1_RX_3 | PIN_INPUT_PULLUP) /* PTC6 */
#define PIN_LPUART1_TX PIN_LPUART1_TX_3 /* PTC7 */ #define PIN_LPUART1_TX PIN_LPUART1_TX_3 /* PTC7 */
/* LPUART4 /dev/ttyS3 P8B 3X7 Pin 3 Single wire RC UART */
#define PIN_LPUART4_RX PIN_LPUART4_TX_3 /* Dummy since it's Single Wire TX-only */
#define PIN_LPUART4_TX PIN_LPUART4_TX_3 /* PTE11 */
/* LPUART7 /dev/ttyS4 P8B 3X7 Pin 3 and Pin 8 */
#define PIN_LPUART7_RX (PIN_LPUART7_RX_3 | PIN_INPUT_PULLUP) /* PTE0 */
#define PIN_LPUART7_TX PIN_LPUART7_TX_3 /* PTE1 */
/* LPUART9 P24 UART connector */ /* LPUART9 P24 UART connector */
#define PIN_LPUART9_RX (PIN_LPUART9_RX_1 | PIN_INPUT_PULLUP) /* PTB2 */ #define PIN_LPUART9_RX (PIN_LPUART9_RX_1 | PIN_INPUT_PULLUP) /* PTB2 */
@ -209,7 +221,8 @@
#define PIN_LPSPI4_PCS0 PIN_LPSPI4_PCS0_1 /* PTB8 */ #define PIN_LPSPI4_PCS0 PIN_LPSPI4_PCS0_1 /* PTB8 */
#define PIN_LPSPI4_PCS3 PIN_LPSPI4_PCS3_1 /* PTA16 */ #define PIN_LPSPI4_PCS3 PIN_LPSPI4_PCS3_1 /* PTA16 */
#define PIN_LPSPI4_PCS (PIN_PTA16 | GPIO_LOWDRIVE | GPIO_OUTPUT_ONE) /* PTA16 */ #define PIN_LPSPI4_CS_P26 (PIN_PTA16 | GPIO_LOWDRIVE | GPIO_OUTPUT_ONE) /* PTA16 */
#define PIN_LPSPI4_CS_P8B (PIN_PTB8 | GPIO_LOWDRIVE | GPIO_OUTPUT_ONE) /* PTB8 */
/* LPSPI5 P26 external IMU connector */ /* LPSPI5 P26 external IMU connector */

View File

@ -245,6 +245,8 @@ CONFIG_S32K3XX_LPUART13=y
CONFIG_S32K3XX_LPUART14=y CONFIG_S32K3XX_LPUART14=y
CONFIG_S32K3XX_LPUART1=y CONFIG_S32K3XX_LPUART1=y
CONFIG_S32K3XX_LPUART2=y CONFIG_S32K3XX_LPUART2=y
CONFIG_S32K3XX_LPUART4=y
CONFIG_S32K3XX_LPUART7=y
CONFIG_S32K3XX_LPUART9=y CONFIG_S32K3XX_LPUART9=y
CONFIG_S32K3XX_LPUART_INVERT=y CONFIG_S32K3XX_LPUART_INVERT=y
CONFIG_S32K3XX_LPUART_SINGLEWIRE=y CONFIG_S32K3XX_LPUART_SINGLEWIRE=y

View File

@ -38,6 +38,7 @@ if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
clockconfig.c clockconfig.c
periphclocks.c periphclocks.c
timer_config.cpp timer_config.cpp
hw_rev_ver_canhubk3.c
) )
target_link_libraries(drivers_board target_link_libraries(drivers_board
@ -65,6 +66,8 @@ else()
spi.cpp spi.cpp
timer_config.cpp timer_config.cpp
s32k3xx_userleds.c s32k3xx_userleds.c
hw_rev_ver_canhubk3.c
manifest.c
) )
target_link_libraries(drivers_board target_link_libraries(drivers_board

View File

@ -88,7 +88,7 @@ __BEGIN_DECLS
#define DIRECT_PWM_OUTPUT_CHANNELS 8 #define DIRECT_PWM_OUTPUT_CHANNELS 8
#define RC_SERIAL_PORT "/dev/ttyS5" #define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE #define RC_SERIAL_SINGLEWIRE_FORCE
#define RC_SERIAL_INVERT_RX_ONLY #define RC_SERIAL_INVERT_RX_ONLY
#define BOARD_ENABLE_CONSOLE_BUFFER #define BOARD_ENABLE_CONSOLE_BUFFER
@ -110,6 +110,40 @@ __BEGIN_DECLS
/* Reboot and ulog we store on a wear-level filesystem */ /* Reboot and ulog we store on a wear-level filesystem */
#define HARDFAULT_REBOOT_PATH "/mnt/progmem/reboot" #define HARDFAULT_REBOOT_PATH "/mnt/progmem/reboot"
/* To detect MR-CANHUBK3-ADAP board */
#define BOARD_HAS_HW_VERSIONING 1
#define CANHUBK3_ADAP_DETECT (PIN_PTA12 | GPIO_INPUT | GPIO_PULLUP)
/*
* 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. ADC1 has 32 channels, with some a/b selection overlap
* in the AD4-AD7 range on the same ADC.
*
* Only ADC1 is used
* Bits 31:0 are ADC1 channels 31:0
*/
#define ADC1_CH(c) (((c) & 0x1f)) /* Define ADC number Channel number */
/* ADC defines to be used in sensors.cpp to read from a particular channel */
#define ADC_BATTERY_VOLTAGE_CHANNEL ADC1_CH(0) /* BAT_VSENS 85 PTB4 ADC1_SE10 */
#define ADC_BATTERY_CURRENT_CHANNEL ADC1_CH(1) /* Non-existant but needed for compilation */
/* Mask use to initialize the ADC driver */
#define ADC_CHANNELS ((1 << ADC_BATTERY_VOLTAGE_CHANNEL))
/* Safety Switch
* TBD
*/
#define GPIO_LED_SAFETY (PIN_PTE26 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO)
#define GPIO_BTN_SAFETY (PIN_PTA11 | GPIO_INPUT | GPIO_PULLDOWN)
/**************************************************************************** /****************************************************************************
* Public Data * Public Data
****************************************************************************/ ****************************************************************************/

View File

@ -0,0 +1,142 @@
/****************************************************************************
*
* Copyright (C) 2023 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 hw_rev_ver_canhubk3.c
* CANHUBK3 Hardware Revision and Version ID API
*/
#include <drivers/drv_adc.h>
#include <px4_arch/adc.h>
#include <px4_platform_common/micro_hal.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform/board_determine_hw_info.h>
#include <stdio.h>
#include <board_config.h>
#include <systemlib/px4_macros.h>
#if defined(BOARD_HAS_HW_VERSIONING)
#define HW_INFO_SIZE HW_INFO_VER_DIGITS + HW_INFO_REV_DIGITS
/****************************************************************************
* Private Data
****************************************************************************/
static int is_adap_connected = 0;
/****************************************************************************
* Public Functions
****************************************************************************/
/************************************************************************************
* Name: board_get_hw_type
*
* Description:
* Optional returns a 0 terminated string defining the HW type.
*
* Input Parameters:
* None
*
* Returned Value:
* a 0 terminated string defining the HW type. This my be a 0 length string ""
*
************************************************************************************/
__EXPORT const char *board_get_hw_type_name()
{
if (is_adap_connected) {
return (const char *)"MR-CANHUBK3-ADAP";
} else {
return (const char *)"MR-CANHUBK344";
}
}
/************************************************************************************
* Name: board_get_hw_version
*
* Description:
* Optional returns a integer HW version
*
* Input Parameters:
* None
*
* Returned Value:
* An integer value of this boards hardware version.
* A value of -1 is the default for boards not supporting the BOARD_HAS_VERSIONING API.
* A value of 0 is the default for boards supporting the API but not having version.
*
************************************************************************************/
__EXPORT int board_get_hw_version()
{
return 0;
}
/************************************************************************************
* Name: board_get_hw_revision
*
* Description:
* Optional returns a integer HW revision
*
* Input Parameters:
* None
*
* Returned Value:
* An integer value of this boards hardware revision.
* A value of -1 is the default for boards not supporting the BOARD_HAS_VERSIONING API.
* A value of 0 is the default for boards supporting the API but not having revision.
*
************************************************************************************/
__EXPORT int board_get_hw_revision()
{
return 0;
}
/************************************************************************************
* Name: board_determine_hw_info
*
* Description:
* Uses GPIO to detect MR-CANHUBK3-ADAP
*
************************************************************************************/
int board_determine_hw_info()
{
s32k3xx_pinconfig(CANHUBK3_ADAP_DETECT);
is_adap_connected = !s32k3xx_gpioread(CANHUBK3_ADAP_DETECT);
return 0;
}
#endif

View File

@ -34,6 +34,6 @@
#include <px4_arch/i2c_hw_description.h> #include <px4_arch/i2c_hw_description.h>
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusInternal(PX4_BUS_NUMBER_TO_PX4(0)), initI2CBusExternal(PX4_BUS_NUMBER_TO_PX4(0)),
initI2CBusExternal(PX4_BUS_NUMBER_TO_PX4(1)), initI2CBusInternal(PX4_BUS_NUMBER_TO_PX4(1)),
}; };

View File

@ -44,6 +44,7 @@
#include "board_config.h" #include "board_config.h"
#include <px4_platform_common/init.h> #include <px4_platform_common/init.h>
#include <px4_platform/board_determine_hw_info.h>
#if defined(CONFIG_S32K3XX_LPSPI1) && defined(CONFIG_MMCSD) #if defined(CONFIG_S32K3XX_LPSPI1) && defined(CONFIG_MMCSD)
#include <nuttx/mmcsd.h> #include <nuttx/mmcsd.h>
@ -96,6 +97,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
int rv; int rv;
board_determine_hw_info();
#if defined(CONFIG_S32K3XX_LPSPI1) && defined(CONFIG_MMCSD) #if defined(CONFIG_S32K3XX_LPSPI1) && defined(CONFIG_MMCSD)
/* LPSPI1 *****************************************************************/ /* LPSPI1 *****************************************************************/

View File

@ -0,0 +1,79 @@
/****************************************************************************
*
* Copyright (c) 2023 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 <px4_platform_common/px4_config.h>
#include <stdbool.h>
#include <syslog.h>
#include "systemlib/px4_macros.h"
#include "px4_log.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/************************************************************************************
* 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)
{
return px4_hw_mft_unsupported;
}

View File

@ -107,6 +107,9 @@ int s32k3xx_bringup(void)
s32k3xx_spidev_initialize(); s32k3xx_spidev_initialize();
#endif #endif
s32k3xx_pinconfig(GPIO_LED_SAFETY);
s32k3xx_pinconfig(GPIO_BTN_SAFETY);
#ifdef CONFIG_INPUT_BUTTONS #ifdef CONFIG_INPUT_BUTTONS
/* Register the BUTTON driver */ /* Register the BUTTON driver */

View File

@ -168,6 +168,22 @@ const struct peripheral_clock_config_s g_peripheral_clockconfig0[] = {
.clkgate = true, .clkgate = true,
#else #else
.clkgate = false, .clkgate = false,
#endif
},
{
.clkname = LPUART4_CLK,
#ifdef CONFIG_S32K3XX_LPUART4
.clkgate = true,
#else
.clkgate = false,
#endif
},
{
.clkname = LPUART7_CLK,
#ifdef CONFIG_S32K3XX_LPUART7
.clkgate = true,
#else
.clkgate = false,
#endif #endif
}, },
{ {
@ -258,6 +274,10 @@ const struct peripheral_clock_config_s g_peripheral_clockconfig0[] = {
.clkname = EMIOS0_CLK, .clkname = EMIOS0_CLK,
.clkgate = true, .clkgate = true,
}, },
{
.clkname = ADC2_CLK,
.clkgate = true,
}
}; };
unsigned int const num_of_peripheral_clocks_0 = unsigned int const num_of_peripheral_clocks_0 =

View File

@ -70,11 +70,12 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI3, { // SPI3 is ignored only used for FS26 by a NuttX driver initSPIBus(SPI::Bus::SPI3, { // SPI3 is ignored only used for FS26 by a NuttX driver
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin17}) initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin17})
}), }),
initSPIBus(SPI::Bus::SPI4, { initSPIBusExternal(SPI::Bus::SPI4, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortA, GPIO::Pin16}, SPI::DRDY{PIN_WKPU20}) initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin16}, SPI::DRDY{PIN_WKPU20}),
initSPIConfigExternal(SPI::CS{GPIO::PortB, GPIO::Pin8}, SPI::DRDY{PIN_WKPU56})
}), }),
initSPIBus(SPI::Bus::SPI5, { initSPIBusExternal(SPI::Bus::SPI5, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortA, GPIO::Pin14}, SPI::DRDY{PIN_WKPU4}) initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin14}, SPI::DRDY{PIN_WKPU4})
}), }),
}; };
@ -337,7 +338,14 @@ void s32k3xx_lpspi4select(FAR struct spi_dev_s *dev, uint32_t devid,
spiinfo("devid: %" PRId32 ", CS: %s\n", devid, spiinfo("devid: %" PRId32 ", CS: %s\n", devid,
selected ? "assert" : "de-assert"); selected ? "assert" : "de-assert");
s32k3xx_gpiowrite(PIN_LPSPI4_PCS, !selected); devid = ((devid) & 0xF);
if (devid == 0) {
s32k3xx_gpiowrite(PIN_LPSPI4_CS_P26, !selected);
} else if (devid == 1) {
s32k3xx_gpiowrite(PIN_LPSPI4_CS_P8B, !selected);
}
} }
uint8_t s32k3xx_lpspi4status(FAR struct spi_dev_s *dev, uint32_t devid) uint8_t s32k3xx_lpspi4status(FAR struct spi_dev_s *dev, uint32_t devid)

View File

@ -13,6 +13,7 @@ CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PWM_OUT=y
CONFIG_BOARD_UAVCAN_INTERFACES=1 CONFIG_BOARD_UAVCAN_INTERFACES=1
CONFIG_DRIVERS_UAVCANNODE=y CONFIG_DRIVERS_UAVCANNODE=y
CONFIG_DRIVERS_UWB_UWB_SR150=y
CONFIG_UAVCANNODE_ARMING_STATUS=y CONFIG_UAVCANNODE_ARMING_STATUS=y
CONFIG_UAVCANNODE_BEEP_COMMAND=y CONFIG_UAVCANNODE_BEEP_COMMAND=y
CONFIG_UAVCANNODE_ESC_RAW_COMMAND=y CONFIG_UAVCANNODE_ESC_RAW_COMMAND=y

View File

@ -5,5 +5,3 @@
param set-default BAT1_V_DIV 10.177939394 param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303 param set-default BAT1_A_PER_V 15.391030303
param set-default SYS_USE_IO 1

View File

@ -5,5 +5,3 @@
param set-default BAT1_V_DIV 10.177939394 param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303 param set-default BAT1_A_PER_V 15.391030303
param set-default SYS_USE_IO 1

View File

@ -13,6 +13,4 @@ param set-default BAT2_A_PER_V 26.4
param set-default EKF2_MULTI_IMU 2 param set-default EKF2_MULTI_IMU 2
param set-default SENS_IMU_MODE 0 param set-default SENS_IMU_MODE 0
param set-default SYS_USE_IO 1
set LOGGER_BUF 64 set LOGGER_BUF 64

View File

@ -9,13 +9,6 @@ param set-default BAT2_V_DIV 18.1
param set-default BAT1_A_PER_V 36.367515152 param set-default BAT1_A_PER_V 36.367515152
param set-default BAT2_A_PER_V 36.367515152 param set-default BAT2_A_PER_V 36.367515152
if ver hwtypecmp V5004000 V5006000
then
param set-default SYS_USE_IO 0
else
param set-default SYS_USE_IO 1
fi
if ver hwtypecmp V5005000 V5005002 V5006000 V5006002 if ver hwtypecmp V5005000 V5005002 V5006000 V5006002
then then
# CUAV V5+ (V550/V552) and V5nano (V560/V562) have 3 IMUs # CUAV V5+ (V550/V552) and V5nano (V560/V562) have 3 IMUs

View File

@ -10,3 +10,7 @@ CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n
CONFIG_BOARD_TESTING=y CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_TEST_PPM=y CONFIG_DRIVERS_TEST_PPM=y
CONFIG_SYSTEMCMDS_MICROBENCH=y CONFIG_SYSTEMCMDS_MICROBENCH=y
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_FW_POS_CONTROL=n
CONFIG_MODULES_FW_RATE_CONTROL=n

View File

@ -0,0 +1,49 @@
############################################################################
#
# 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.
#
############################################################################
set(PX4_FW_NAME ${PX4_BINARY_DIR}/${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_${PX4_BOARD_LABEL}.px4)
add_custom_target(upload_skynode_usb
COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME}
DEPENDS ${PX4_FW_NAME}
COMMENT "Uploading PX4"
USES_TERMINAL
)
add_custom_target(upload_skynode_wifi
COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME} --wifi
DEPENDS ${PX4_FW_NAME}
COMMENT "Uploading PX4"
USES_TERMINAL
)

View File

@ -16,6 +16,4 @@ param set-default SENS_EN_INA238 0
param set-default SENS_EN_INA228 0 param set-default SENS_EN_INA228 0
param set-default SENS_EN_INA226 1 param set-default SENS_EN_INA226 1
param set-default SYS_USE_IO 1
safety_button start safety_button start

View File

@ -3,7 +3,7 @@
# board specific MAVLink startup script. # board specific MAVLink startup script.
#------------------------------------------------------------------------------ #------------------------------------------------------------------------------
if ver hwtypecmp V5X009000 V5X009001 V5X00a000 V5X00a001 V5X008000 V5X008001 V5X010001 if ver hwbasecmp 008 009 00a 010
then then
# Start MAVLink on the UART connected to the mission computer # Start MAVLink on the UART connected to the mission computer
mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z

View File

@ -5,7 +5,7 @@
set HAVE_PM2 yes set HAVE_PM2 yes
if ver hwtypecmp V5X005000 V5X005001 V5X005002 if mft query -q -k MFT -s MFT_PM2 -v 0
then then
set HAVE_PM2 no set HAVE_PM2 no
fi fi
@ -49,33 +49,11 @@ then
fi fi
fi fi
if ver hwtypecmp V5X000000 V5X000001 V5X000002 V5X001000 V5X004000 V5X004001 V5X004002 V5X005001 V5X005002 if ver hwbasecmp 008 009 00a 010
then then
#FMUv5Xbase board orientation
if ver hwtypecmp V5X000000 V5X000001 V5X004000 V5X004001 V5X005001
then
# Internal SPI BMI088
bmi088 -A -R 4 -s start
bmi088 -G -R 4 -s start
else
# Internal SPI bus ICM20649
icm20649 -s -R 6 start
fi
# Internal SPI bus ICM42688p
icm42688p -R 6 -s start
# Internal SPI bus ICM-20602 (hard-mounted)
icm20602 -R 10 -s start
# Internal magnetometer on I2c
bmm150 -I start
else
#SKYNODE base fmu board orientation #SKYNODE base fmu board orientation
if ver hwtypecmp V5X009000 V5X009001 V5X00a000 V5X00a001 V5X008000 V5X008001 V5X010001 if ver hwtypecmp V5X000 V5X001
then then
# Internal SPI BMI088 # Internal SPI BMI088
bmi088 -A -R 2 -s start bmi088 -A -R 2 -s start
@ -105,7 +83,7 @@ ist8310 -X -b 1 -R 10 start
if param compare SENS_INT_BARO_EN 1 if param compare SENS_INT_BARO_EN 1
then then
bmp388 -I -a 0x77 start bmp388 -I -a 0x77 start
if ver hwtypecmp V5X000000 V5X001000 V5X008000 V5X009000 V5X00a000 if ver hwtypecmp V5X000
then then
bmp388 -I start bmp388 -I start
else else

View File

@ -36,7 +36,6 @@ add_library(drivers_board
i2c.cpp i2c.cpp
init.cpp init.cpp
led.c led.c
manifest.c
mtd.cpp mtd.cpp
sdio.c sdio.c
spi.cpp spi.cpp

View File

@ -179,31 +179,17 @@
/* HW Version and Revision drive signals Default to 1 to detect */ /* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING #define BOARD_HAS_HW_SPLIT_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_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
#define GPIO_HW_REV_SENSE /* PF5 */ ADC3_GPIO(15) #define GPIO_HW_REV_SENSE /* PF5 */ ADC3_GPIO(15)
#define GPIO_HW_VER_SENSE /* PF4 */ ADC3_GPIO(14) #define GPIO_HW_VER_SENSE /* PF4 */ ADC3_GPIO(14)
#define HW_INFO_INIT_PREFIX "V5X" #define HW_INFO_INIT_PREFIX "V5X"
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 7 #define BOARD_NUM_SPI_CFG_HW_VERSIONS 3
// Base FMUM
#define V5X00 HW_VER_REV(0x0,0x0) // FMUV5X, Rev 0 #define V5X_0 HW_FMUM_ID(0x0) // FMUV5X, Auterion FMUv5x RC13 (baro2 BMP388 on I2C4) Sensor Set Rev 0
#define V5X10 HW_VER_REV(0x1,0x0) // NO PX4IO, Rev 0 #define V5X_1 HW_FMUM_ID(0x1) // FMUV5X, Auterion, HB FMUv5x RC15 (baro2 BMP388 on I2C2) Sensor Set Rev 1
#define V5X01 HW_VER_REV(0x0,0x1) // FMUV5X I2C2 BMP388, Rev 1 #define V5X_2 HW_FMUM_ID(0x2) // FMUV5X, HB FMUv5x Sensor Set Rev 2
#define V5X02 HW_VER_REV(0x0,0x2) // FMUV5X, Rev 2
#define V5X40 HW_VER_REV(0x4,0x0) // FMUV5X, HB CM4 base Rev 0
#define V5X41 HW_VER_REV(0x4,0x1) // FMUV5X I2C2 BMP388, HB CM4 base Rev 1
#define V5X42 HW_VER_REV(0x4,0x2) // FMUV5X, HB CM4 base Rev 2
#define V5X50 HW_VER_REV(0x5,0x0) // FMUV5X, HB Mini Rev 0
#define V5X51 HW_VER_REV(0x5,0x1) // FMUV5X I2C2 BMP388, HB Mini Rev 1
#define V5X52 HW_VER_REV(0x5,0x2) // FMUV5X, HB Mini Rev 2
#define V5X90 HW_VER_REV(0x9,0x0) // NO USB, Rev 0
#define V5X91 HW_VER_REV(0x9,0x1) // NO USB I2C2 BMP388, Rev 1
#define V5X92 HW_VER_REV(0x9,0x2) // NO USB I2C2 BMP388, Rev 2
#define V5Xa0 HW_VER_REV(0xa,0x0) // NO USB (Q), Rev 0
#define V5Xa1 HW_VER_REV(0xa,0x1) // NO USB (Q) I2C2 BMP388, Rev 1
#define V5Xa2 HW_VER_REV(0xa,0x2) // NO USB (Q) I2C2 BMP388, Rev 2
#define V5X101 HW_VER_REV(0x10,0x1) // NO USB (Q) I2C2 BMP388, Rev 1
#define UAVCAN_NUM_IFACES_RUNTIME 1 #define UAVCAN_NUM_IFACES_RUNTIME 1

View File

@ -1,222 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2018-2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file manifest.c
*
* This module supplies the interface to the manifest of hardware that is
* optional and dependent on the HW REV and HW VER IDs
*
* The manifest allows the system to know whether a hardware option
* say for example the PX4IO is an no-pop option vs it is broken.
*
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <inttypes.h>
#include <stdbool.h>
#include <syslog.h>
#include "systemlib/px4_macros.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
typedef struct {
uint32_t hw_ver_rev; /* the version and revision */
const px4_hw_mft_item_t *mft; /* The first entry */
uint32_t entries; /* the lenght of the list */
} px4_hw_mft_list_entry_t;
typedef px4_hw_mft_list_entry_t *px4_hw_mft_list_entry;
#define px4_hw_mft_list_uninitialized (px4_hw_mft_list_entry) -1
static const px4_hw_mft_item_t device_unsupported = {0, 0, 0};
// List of components on a specific board configuration
// The index of those components is given by the enum (px4_hw_mft_item_id_t)
// declared in board_common.h
static const px4_hw_mft_item_t hw_mft_list_v0500[] = {
{
// 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_v0550[] = {
{
// 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 = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
};
static const px4_hw_mft_item_t hw_mft_list_v0510[] = {
{
// 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_v0509[] = {
{
// PX4_MFT_PX4IO
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
// PX4_MFT_USB
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
{
// PX4_MFT_CAN2
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
};
static px4_hw_mft_list_entry_t mft_lists[] = {
// ver_rev
{V5X00, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // FMUV5X, Rev 0
{V5X01, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // FMUV5X, Rev 1
{V5X02, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // FMUV5X, Rev 2
{V5X10, hw_mft_list_v0510, arraySize(hw_mft_list_v0510)}, // NO PX4IO, Rev 0
{V5X41, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // FMUV5X, HB CM4 base Rev 1
{V5X42, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // FMUV5X, HB CM4 base Rev 2
{V5X51, hw_mft_list_v0550, arraySize(hw_mft_list_v0550)}, // FMUV5X, HB Mini Rev 1
{V5X52, hw_mft_list_v0550, arraySize(hw_mft_list_v0550)}, // FMUV5X, HB Mini Rev 2
{V5X90, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB, Rev 0
{V5X91, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB I2C2 BMP388, Rev 1
{V5X92, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB I2C2 BMP388, Rev 2
{V5Xa0, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q), Rev 0
{V5Xa1, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q) I2C2 BMP388, Rev 1
{V5Xa2, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q) I2C2 BMP388, Rev 2
{V5X101, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB I2C2 BMP388, Rev 1
};
/************************************************************************************
* Name: board_query_manifest
*
* Description:
* Optional returns manifest item.
*
* Input Parameters:
* manifest_id - the ID for the manifest item to retrieve
*
* Returned Value:
* 0 - item is not in manifest => assume legacy operations
* pointer to a manifest item
*
************************************************************************************/
__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
{
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
if (mft_lists[i].hw_ver_rev == ver_rev) {
boards_manifest = &mft_lists[i];
break;
}
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
px4_hw_mft_item rv = &device_unsupported;
if (boards_manifest != px4_hw_mft_list_uninitialized &&
id < boards_manifest->entries) {
rv = &boards_manifest->mft[id];
}
return rv;
}

View File

@ -31,6 +31,9 @@
* *
****************************************************************************/ ****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <nuttx/spi/spi.h> #include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h> #include <px4_platform_common/px4_manifest.h>
// KiB BS nB // KiB BS nB
@ -120,10 +123,16 @@ static const px4_mft_entry_s mtd_mft = {
.pmft = (void *) &board_mtd_config, .pmft = (void *) &board_mtd_config,
}; };
static const px4_mft_entry_s mft_mft = {
.type = MFT,
.pmft = (void *) system_query_manifest,
};
static const px4_mft_s mft = { static const px4_mft_s mft = {
.nmft = 1, .nmft = 2,
.mfts = { .mfts = {
&mtd_mft &mtd_mft,
&mft_mft,
} }
}; };

View File

@ -36,7 +36,7 @@
#include <nuttx/spi/spi.h> #include <nuttx/spi/spi.h>
constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = { constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = {
initSPIHWVersion(V5X00, { initSPIFmumID(V5X_0, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
@ -60,7 +60,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
}), }),
}), }),
initSPIHWVersion(V5X01, { initSPIFmumID(V5X_1, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
@ -84,7 +84,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
}), }),
}), }),
initSPIHWVersion(V5X02, { initSPIFmumID(V5X_2, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
@ -107,99 +107,6 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
}), }),
}), }),
initSPIHWVersion(V5X41, {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, 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::PortH, GPIO::Pin12}),
}, {GPIO::PortD, GPIO::Pin15}),
initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}),
}, {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(V5X42, {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, 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::PortH, GPIO::Pin12}),
}, {GPIO::PortD, GPIO::Pin15}),
initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
}, {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(V5X51, {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, 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::PortH, GPIO::Pin12}),
}, {GPIO::PortD, GPIO::Pin15}),
initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}),
}, {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(V5X52, {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, 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::PortH, GPIO::Pin12}),
}, {GPIO::PortD, GPIO::Pin15}),
initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
}, {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); static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw);

View File

@ -9,5 +9,3 @@ param set-default BAT2_V_DIV 18.1
param set-default BAT1_A_PER_V 36.367515152 param set-default BAT1_A_PER_V 36.367515152
param set-default BAT2_A_PER_V 36.367515152 param set-default BAT2_A_PER_V 36.367515152
param set-default SYS_USE_IO 1

View File

@ -0,0 +1,49 @@
############################################################################
#
# Copyright (c) 2023 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.
#
############################################################################
set(PX4_FW_NAME ${PX4_BINARY_DIR}/${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_${PX4_BOARD_LABEL}.px4)
add_custom_target(upload_skynode_usb
COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME}
DEPENDS ${PX4_FW_NAME}
COMMENT "Uploading PX4"
USES_TERMINAL
)
add_custom_target(upload_skynode_wifi
COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME} --wifi
DEPENDS ${PX4_FW_NAME}
COMMENT "Uploading PX4"
USES_TERMINAL
)

View File

@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3"
CONFIG_DRIVERS_ADC_ADS1115=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_DRIVERS_BAROMETER_BMP388=y
CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y
@ -19,28 +20,32 @@ CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_HEATER=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16470=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42670P=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42670P=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
CONFIG_COMMON_INS=y CONFIG_COMMON_INS=y
CONFIG_COMMON_LIGHT=y CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_OSD=y CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y CONFIG_DRIVERS_PX4IO=y
CONFIG_COMMON_RC=y
CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_DRIVERS_TONE_ALARM=y CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y CONFIG_DRIVERS_UAVCAN=y
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2
CONFIG_MODULES_AIRSPEED_SELECTOR=y CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y CONFIG_MODULES_CONTROL_ALLOCATOR=y

View File

@ -16,6 +16,5 @@ param set-default SENS_EN_INA238 0
param set-default SENS_EN_INA228 0 param set-default SENS_EN_INA228 0
param set-default SENS_EN_INA226 1 param set-default SENS_EN_INA226 1
param set-default SYS_USE_IO 1
safety_button start safety_button start

View File

@ -4,7 +4,7 @@
#------------------------------------------------------------------------------ #------------------------------------------------------------------------------
set HAVE_PM2 yes set HAVE_PM2 yes
if ver hwtypecmp V6X005000 V6X005001 V6X005003 V6X005004 if mft query -q -k MFT -s MFT_PM2 -v 0
then then
set HAVE_PM2 no set HAVE_PM2 no
fi fi
@ -48,67 +48,79 @@ then
fi fi
if ver hwtypecmp V6X000004 V6X001004 V6X004004 V6X005004 # Keep nesting shallow
if ver hwtypecmp V6X006 V6X008
then then
# Internal SPI bus ICM20649 if ver hwtypecmp V6X006
icm20649 -s -R 6 start
else
# Internal SPI BMI088
if ver hwtypecmp V6X009010 V6X010010
then then
bmi088 -A -R 6 -s start # Internal SPI bus ICM45686
bmi088 -G -R 6 -s start adis16470 -s -R 0 start
iim42652 -s -R 6 start
icm45686 -s -R 10 start
else else
if ver hwtypecmp V6X000010 # Internal SPI bus 3x ICM45686
icm45686 -b 3 -s -R 0 start
icm45686 -b 2 -s -R 0 start
icm45686 -b 1 -s -R 10 start
fi
else
if ver hwtypecmp V6X004
then
# Internal SPI bus ICM20649
icm20649 -s -R 6 start
else
# Internal SPI BMI088
if ver hwbasecmp 009 010
then then
bmi088 -A -R 0 -s start bmi088 -A -R 6 -s start
bmi088 -G -R 0 -s start bmi088 -G -R 6 -s start
else else
bmi088 -A -R 4 -s start if ver hwtypecmp V6X010
bmi088 -G -R 4 -s start then
bmi088 -A -R 0 -s start
bmi088 -G -R 0 -s start
else
bmi088 -A -R 4 -s start
bmi088 -G -R 4 -s start
fi
fi
fi
# Internal SPI bus ICM42688p
if ver hwbasecmp 009 010
then
icm42688p -R 12 -s start
else
if ver hwtypecmp V6X010
then
icm42688p -R 14 -s start
else
icm42688p -R 6 -s start
fi
fi
if ver hwtypecmp V6X003 V6X004
then
# Internal SPI bus ICM-42670-P (hard-mounted)
icm42670p -R 10 -s start
else
if ver hwbasecmp 009 010
then
icm20602 -R 6 -s start
else
# Internal SPI bus ICM-20649 (hard-mounted)
icm20649 -R 14 -s start
fi fi
fi fi
fi fi
# Internal SPI bus ICM42688p
if ver hwtypecmp V6X009010 V6X010010
then
icm42688p -R 12 -s start
else
if ver hwtypecmp V6X000010
then
icm42688p -R 14 -s start
else
icm42688p -R 6 -s start
fi
fi
if ver hwtypecmp V6X000003 V6X001003 V6X003003 V6X000004 V6X001004 V6X004003 V6X004004 V6X005003 V6X005004
then
# Internal SPI bus ICM-42670-P (hard-mounted)
icm42670p -R 10 -s start
else
if ver hwtypecmp V6X009010 V6X010010
then
icm20602 -R 6 -s start
else
# Internal SPI bus ICM-20649 (hard-mounted)
icm20649 -R 14 -s start
fi
fi
# Internal magnetometer on I2c # Internal magnetometer on I2c
if ver hwtypecmp V6X002001 if ver hwtypecmp V6X001
then then
rm3100 -I -b 4 start rm3100 -I -b 4 start
else else
if ver hwtypecmp V6X009010 V6X010010 # Internal magnetometer on I2C
then bmm150 -I -R 0 start
# Internal magnetometer on I2C
bmm150 -I -R 0 start
else
bmm150 -I -R 6 start
fi
fi fi
# 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) # 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)
@ -117,7 +129,7 @@ ist8310 -X -b 1 -R 10 start
# Possible internal Baro # Possible internal Baro
if param compare SENS_INT_BARO_EN 1 if param compare SENS_INT_BARO_EN 1
then then
if ver hwtypecmp V6X002001 if ver hwtypecmp V6X001 V6X006 V6X008
then then
icp201xx -I -a 0x64 start icp201xx -I -a 0x64 start
else else
@ -126,7 +138,7 @@ then
fi fi
#external baro #external baro
if ver hwtypecmp V6X002001 if ver hwtypecmp V6X001
then then
icp201xx -X start icp201xx -X start
else else

View File

@ -380,7 +380,9 @@
#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */ #define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */
#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */ #define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */
// GPIO_UART5_RTS no remap /* PC8 */ // GPIO_UART5_RTS no remap /* PC8 */
// GPIO_UART5_CTS No remap /* PC9 */ #undef GPIO_UART5_CTS
#define GPIO_UART5_CTS ((GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN9) | GPIO_PULLDOWN) /* PC9 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ #define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ #define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */

View File

@ -55,7 +55,6 @@ else()
init.c init.c
led.c led.c
mtd.cpp mtd.cpp
manifest.c
sdio.c sdio.c
spi.cpp spi.cpp
timer_config.cpp timer_config.cpp

View File

@ -208,36 +208,22 @@
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) #define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* HW Version and Revision drive signals Default to 1 to detect */ /* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING #define BOARD_HAS_HW_SPLIT_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_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_REV_SENSE /* PH4 */ GPIO_ADC3_INP15
#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14 #define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14
#define HW_INFO_INIT_PREFIX "V6X" #define HW_INFO_INIT_PREFIX "V6X"
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 11 // Rev 0 and Rev 3,4 Sensor sets #define BOARD_NUM_SPI_CFG_HW_VERSIONS 7
// Base/FMUM // Base/FMUM
#define V6X00 HW_VER_REV(0x0,0x0) // FMUV6X, Rev 0 #define V6X_0 HW_FMUM_ID(0x0) // FMUV6X, Auterion,HB Sensor Set Rev 0
#define V6X01 HW_VER_REV(0x0,0x1) // FMUV6X, BMI388 I2C2 Rev 1 #define V6X_1 HW_FMUM_ID(0x1) // FMUV6X, CUAV Sensor Set Rev 1
#define V6X03 HW_VER_REV(0x0,0x3) // FMUV6X, Sensor Set Rev 3 #define V6X_3 HW_FMUM_ID(0x3) // FMUV6X, HB Sensor Set Rev 3
#define V6X04 HW_VER_REV(0x0,0x4) // FMUV6X, Sensor Set Rev 4 #define V6X_4 HW_FMUM_ID(0x4) // FMUV6X, HB Sensor Set Rev 4
#define V6X10 HW_VER_REV(0x1,0x0) // NO PX4IO, Rev 0 #define V6X_6 HW_FMUM_ID(0x6) // FMUV6X, HB Sensor Set Rev 6
#define V6X13 HW_VER_REV(0x1,0x3) // NO PX4IO, Sensor Set Rev 3 #define V6X_8 HW_FMUM_ID(0x8) // FMUV6X, HB Sensor Set Rev 8
#define V6X14 HW_VER_REV(0x1,0x4) // NO PX4IO, Sensor Set Rev 4 #define V6X_16 HW_FMUM_ID(0x10) // FMUV6X, Auterion Sensor Set Rev 16 from EEPROM
#define V6X21 HW_VER_REV(0x2,0x1) // FMUV6X, CUAV Sensor Set
#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
#define V6X90 HW_VER_REV(0x9,0x0) // Rev 0
#define V6X0910 HW_VER_REV(0x9,0x10) // FMUV6X, rev from EEPROM Auterion Skynode ver9
#define V6X1010 HW_VER_REV(0x10,0x10) // FMUV6X, rev from EEPROM Auterion Skynode ver10
#define UAVCAN_NUM_IFACES_RUNTIME 1 #define UAVCAN_NUM_IFACES_RUNTIME 1

View File

@ -1,205 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2018-2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file manifest.c
*
* This module supplies the interface to the manifest of hardware that is
* optional and dependent on the HW REV and HW VER IDs
*
* The manifest allows the system to know whether a hardware option
* say for example the PX4IO is an no-pop option vs it is broken.
*
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <inttypes.h>
#include <stdbool.h>
#include <syslog.h>
#include "systemlib/px4_macros.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
typedef struct {
uint32_t hw_ver_rev; /* the version and revision */
const px4_hw_mft_item_t *mft; /* The first entry */
uint32_t entries; /* the lenght of the list */
} px4_hw_mft_list_entry_t;
typedef px4_hw_mft_list_entry_t *px4_hw_mft_list_entry;
#define px4_hw_mft_list_uninitialized (px4_hw_mft_list_entry) -1
static const px4_hw_mft_item_t device_unsupported = {0, 0, 0};
// List of components on a specific board configuration
// The index of those components is given by the enum (px4_hw_mft_item_id_t)
// declared in board_common.h
static const px4_hw_mft_item_t hw_mft_list_v0600[] = {
{
// 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
{V6X21, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)},
{V6X0910, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // FMUV6X, rev from EEPROM Auterion Skynode ver9
{V6X1010, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // FMUV6X, rev from EEPROM Auterion Skynode ver10
};
/************************************************************************************
* Name: board_query_manifest
*
* Description:
* Optional returns manifest item.
*
* Input Parameters:
* manifest_id - the ID for the manifest item to retrieve
*
* Returned Value:
* 0 - item is not in manifest => assume legacy operations
* pointer to a manifest item
*
************************************************************************************/
__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
{
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 16;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
if (mft_lists[i].hw_ver_rev == ver_rev) {
boards_manifest = &mft_lists[i];
break;
}
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
}
}
px4_hw_mft_item rv = &device_unsupported;
if (boards_manifest != px4_hw_mft_list_uninitialized &&
id < boards_manifest->entries) {
rv = &boards_manifest->mft[id];
}
return rv;
}

View File

@ -31,6 +31,9 @@
* *
****************************************************************************/ ****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <nuttx/spi/spi.h> #include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h> #include <px4_platform_common/px4_manifest.h>
// KiB BS nB // KiB BS nB
@ -120,10 +123,16 @@ static const px4_mft_entry_s mtd_mft = {
.pmft = (void *) &board_mtd_config, .pmft = (void *) &board_mtd_config,
}; };
static const px4_mft_entry_s mft_mft = {
.type = MFT,
.pmft = (void *) system_query_manifest,
};
static const px4_mft_s mft = { static const px4_mft_s mft = {
.nmft = 1, .nmft = 2,
.mfts = { .mfts = {
&mtd_mft &mtd_mft,
&mft_mft,
} }
}; };

View File

@ -36,7 +36,7 @@
#include <nuttx/spi/spi.h> #include <nuttx/spi/spi.h>
constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = { constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = {
initSPIHWVersion(V6X00, { initSPIFmumID(V6X_0, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
@ -60,31 +60,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
}), }),
}), }),
initSPIHWVersion(V6X03, { initSPIFmumID(V6X_1, {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42670P, 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_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, 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(V6X21, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
@ -108,7 +84,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
}), }),
}), }),
initSPIHWVersion(V6X43, { initSPIFmumID(V6X_3, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42670P, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_ICM42670P, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
@ -132,31 +108,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
}), }),
}), }),
initSPIHWVersion(V6X50, { initSPIFmumID(V6X_4, {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, 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_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, 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(V6X44, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42670P, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_ICM42670P, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
@ -179,39 +131,15 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
}), }),
}), }),
// never shipped initSPIFmumID(V6X_6, {
//initSPIHWVersion(V6X50, {
// initSPIBus(SPI::Bus::SPI1, {
// initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, 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_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
// initSPIDevice(DRV_ACC_DEVTYPE_BMI088, 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(V6X04, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42670P, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
initSPIBus(SPI::Bus::SPI2, { initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}),
}, {GPIO::PortF, GPIO::Pin4}), }, {GPIO::PortF, GPIO::Pin4}),
initSPIBus(SPI::Bus::SPI3, { initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}), initSPIDevice(DRV_IMU_DEVTYPE_ADIS16470, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
}, {GPIO::PortE, GPIO::Pin7}), }, {GPIO::PortE, GPIO::Pin7}),
// initSPIBus(SPI::Bus::SPI4, { // initSPIBus(SPI::Bus::SPI4, {
// // no devices // // no devices
@ -225,16 +153,16 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}),
}), }),
}), }),
initSPIHWVersion(V6X53, {
initSPIFmumID(V6X_8, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42670P, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
initSPIBus(SPI::Bus::SPI2, { initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}),
}, {GPIO::PortF, GPIO::Pin4}), }, {GPIO::PortF, GPIO::Pin4}),
initSPIBus(SPI::Bus::SPI3, { initSPIBus(SPI::Bus::SPI3, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}), initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}),
}, {GPIO::PortE, GPIO::Pin7}), }, {GPIO::PortE, GPIO::Pin7}),
// initSPIBus(SPI::Bus::SPI4, { // initSPIBus(SPI::Bus::SPI4, {
// // no devices // // no devices
@ -248,52 +176,9 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}),
}), }),
}), }),
initSPIHWVersion(V6X54, {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM42670P, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIFmumID(V6X_16, {
}, {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_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
}, {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(V6X0910, {
initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, 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_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}),
}, {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(V6X1010, {
initSPIBus(SPI::Bus::SPI1, { initSPIBus(SPI::Bus::SPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
}, {GPIO::PortI, GPIO::Pin11}), }, {GPIO::PortI, GPIO::Pin11}),
@ -316,6 +201,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}),
}), }),
}), }),
}; };
static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw); static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw);

View File

@ -38,7 +38,7 @@ else()
endif() endif()
add_custom_target(upload add_custom_target(upload
COMMAND rsync -arh --progress COMMAND rsync -arh --progress -e "ssh -o StrictHostKeyChecking=no"
${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/rpi/*.config ${PX4_BINARY_DIR}/etc # source ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/rpi/*.config ${PX4_BINARY_DIR}/etc # source
pi@${AUTOPILOT_HOST}:/home/pi/px4 # destination pi@${AUTOPILOT_HOST}:/home/pi/px4 # destination
DEPENDS px4 DEPENDS px4

View File

@ -4,15 +4,15 @@ CONFIG_BOARD_TOOLCHAIN="arm-linux-gnueabihf"
CONFIG_BOARD_ARCHITECTURE="cortex-a53" CONFIG_BOARD_ARCHITECTURE="cortex-a53"
CONFIG_BOARD_TESTING=y CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_ADC_ADS1115=y CONFIG_DRIVERS_ADC_ADS1115=y
CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_COMMON_BAROMETERS=y
CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_GPS=y
CONFIG_COMMON_IMU=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_RPI_RC_IN=y CONFIG_DRIVERS_RPI_RC_IN=y

View File

@ -25,8 +25,6 @@ param set-default BAT_V_OFFS_CURR 0.413
# Disable safety switch # Disable safety switch
param set-default CBRK_IO_SAFETY 22027 param set-default CBRK_IO_SAFETY 22027
param set-default SYS_USE_IO 1
safety_button start safety_button start
set LOGGER_BUF 32 set LOGGER_BUF 32

View File

@ -168,7 +168,7 @@
/* HW Version and Revision drive signals Default to 1 to detect */ /* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING #define BOARD_HAS_HW_VERSIONING // migrate to Split
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) #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 /* PF5 */ ADC3_GPIO(15) #define GPIO_HW_REV_SENSE /* PF5 */ ADC3_GPIO(15)

View File

@ -5,5 +5,3 @@
param set-default BAT1_V_DIV 18.1 param set-default BAT1_V_DIV 18.1
param set-default BAT1_A_PER_V 36.367515152 param set-default BAT1_A_PER_V 36.367515152
param set-default SYS_USE_IO 1

View File

@ -5,5 +5,3 @@
param set-default BAT1_V_DIV 18.1 param set-default BAT1_V_DIV 18.1
param set-default BAT1_A_PER_V 36.367515152 param set-default BAT1_A_PER_V 36.367515152
param set-default SYS_USE_IO 1

View File

@ -174,6 +174,7 @@ set(msg_files
SensorSelection.msg SensorSelection.msg
SensorsStatus.msg SensorsStatus.msg
SensorsStatusImu.msg SensorsStatusImu.msg
SensorUwb.msg
SystemPower.msg SystemPower.msg
TakeoffStatus.msg TakeoffStatus.msg
TaskStackInfo.msg TaskStackInfo.msg
@ -190,8 +191,6 @@ set(msg_files
UavcanParameterValue.msg UavcanParameterValue.msg
UlogStream.msg UlogStream.msg
UlogStreamAck.msg UlogStreamAck.msg
UwbDistance.msg
UwbGrid.msg
VehicleAcceleration.msg VehicleAcceleration.msg
VehicleAirData.msg VehicleAirData.msg
VehicleAngularAccelerationSetpoint.msg VehicleAngularAccelerationSetpoint.msg

34
msg/SensorUwb.msg Normal file
View File

@ -0,0 +1,34 @@
# UWB distance contains the distance information measured by an ultra-wideband positioning system,
# such as Pozyx or NXP Rddrone.
uint64 timestamp # time since system start (microseconds)
uint32 sessionid # UWB SessionID
uint32 time_offset # Time between Ranging Rounds in ms
uint32 counter # Number of Ranges since last Start of Ranging
uint16 mac # MAC adress of Initiator (controller)
uint16 mac_dest # MAC adress of Responder (Controlee)
uint16 status # status feedback #
uint8 nlos # None line of site condition y/n
float32 distance # distance in m to the UWB receiver
#Angle of arrival, Angle in Degree -60..+60; FOV in both axis is 120 degrees
float32 aoa_azimuth_dev # Angle of arrival of first incomming RX msg
float32 aoa_elevation_dev # Angle of arrival of first incomming RX msg
float32 aoa_azimuth_resp # Angle of arrival of first incomming RX msg at the responder
float32 aoa_elevation_resp # Angle of arrival of first incomming RX msg at the responder
# Figure of merit for the angle measurements
uint8 aoa_azimuth_fom # AOA Azimuth FOM
uint8 aoa_elevation_fom # AOA Elevation FOM
uint8 aoa_dest_azimuth_fom # AOA Azimuth FOM
uint8 aoa_dest_elevation_fom # AOA Elevation FOM
# Initiator physical configuration
uint8 orientation # Direction the sensor faces from MAV_SENSOR_ORIENTATION enum
# Standard configuration is Antennas facing down and azimuth aligened in forward direction
float32 offset_x # UWB initiator offset in X axis (NED drone frame)
float32 offset_y # UWB initiator offset in Y axis (NED drone frame)
float32 offset_z # UWB initiator offset in Z axis (NED drone frame)

View File

@ -1,15 +0,0 @@
# UWB distance contains the distance information measured by an ultra-wideband positioning system,
# such as Pozyx or NXP Rddrone.
uint64 timestamp # time since system start (microseconds)
uint32 time_uwb_ms # Time of UWB device in ms
uint32 counter # Number of Ranges since last Start of Ranging
uint32 sessionid # UWB SessionID
uint32 time_offset # Time between Ranging Rounds in ms
uint16 status # status feedback #
uint16[12] anchor_distance # distance in cm to each UWB Anchor (UWB Device which takes part in Ranging)
bool[12] nlos # Visual line of sight yes/no
float32[12] aoafirst # Angle of arrival of first incoming RX msg
float32[3] position # Position of the Landing point in relation to the Drone (x,y,z in Meters NED)

View File

@ -1,25 +0,0 @@
# UWB report message contains the grid information measured by an ultra-wideband positioning system,
# such as Pozyx or NXP Rddrone.
uint64 timestamp # time since system start (microseconds)
uint16 initator_time # time to synchronize clocks (microseconds)
uint8 num_anchors # Number of anchors
float64[4] target_gps # GPS position of target of the UWB system (Lat / Lon / Alt / Yaw Offset to true North)
# Grid position information
# Position in x,y,z in (x,y,z in centimeters NED)
# staring with POI and Anchor 0 up to Anchor 11
int16[3] target_pos # Point of Interest, mostly landing Target x,y,z
int16[3] anchor_pos_0
int16[3] anchor_pos_1
int16[3] anchor_pos_2
int16[3] anchor_pos_3
int16[3] anchor_pos_4
int16[3] anchor_pos_5
int16[3] anchor_pos_6
int16[3] anchor_pos_7
int16[3] anchor_pos_8
int16[3] anchor_pos_9
int16[3] anchor_pos_10
int16[3] anchor_pos_11

View File

@ -52,6 +52,7 @@ add_library(px4_platform STATIC
px4_cli.cpp px4_cli.cpp
shutdown.cpp shutdown.cpp
spi.cpp spi.cpp
pab_manifest.c
${SRCS} ${SRCS}
) )
target_link_libraries(px4_platform prebuild_targets px4_work_queue) target_link_libraries(px4_platform prebuild_targets px4_work_queue)

View File

@ -265,6 +265,18 @@
# define HW_VER_REV(v,r) ((uint32_t)((v) & 0xffff) << 16) | ((uint32_t)(r) & 0xffff) # define HW_VER_REV(v,r) ((uint32_t)((v) & 0xffff) << 16) | ((uint32_t)(r) & 0xffff)
#endif #endif
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
typedef uint16_t hw_fmun_id_t;
typedef uint16_t hw_base_id_t;
// Original Signals GPIO_HW_REV_SENSE/GPIO_HW_VER_REV_DRIVE is used to ID the FMUM
// Original Signals GPIO_HW_VER_SENSE/GPIO_HW_VER_REV_DRIVE is used to ID the BASE
# define BOARD_HAS_VERSIONING 1
# define HW_FMUM_ID(rev) ((hw_fmun_id_t)(rev) & 0xffff)
# define HW_BASE_ID(ver) ((hw_base_id_t)(ver) & 0xffff)
# define GET_HW_FMUM_ID() (HW_FMUM_ID(board_get_hw_revision()))
# define GET_HW_BASE_ID() (HW_BASE_ID(board_get_hw_version()))
#endif
#define HW_INFO_REV_DIGITS 3 #define HW_INFO_REV_DIGITS 3
#define HW_INFO_VER_DIGITS 3 #define HW_INFO_VER_DIGITS 3
@ -440,6 +452,8 @@ __BEGIN_DECLS
#if defined(RC_SERIAL_SINGLEWIRE) #if defined(RC_SERIAL_SINGLEWIRE)
static inline bool board_rc_singlewire(const char *device) { return strcmp(device, RC_SERIAL_PORT) == 0; } static inline bool board_rc_singlewire(const char *device) { return strcmp(device, RC_SERIAL_PORT) == 0; }
#elif defined(RC_SERIAL_SINGLEWIRE_FORCE)
static inline bool board_rc_singlewire(const char *device) { return true; }
#else #else
static inline bool board_rc_singlewire(const char *device) { return false; } static inline bool board_rc_singlewire(const char *device) { return false; }
#endif #endif
@ -652,20 +666,51 @@ bool board_booted_by_px4(void);
************************************************************************************/ ************************************************************************************/
typedef enum { typedef enum {
PX4_MFT_PX4IO = 0, PX4_MFT_PX4IO = 0,
PX4_MFT_USB = 1, PX4_MFT_USB = 1,
PX4_MFT_CAN2 = 2, PX4_MFT_CAN2 = 2,
PX4_MFT_CAN3 = 3, PX4_MFT_CAN3 = 3,
PX4_MFT_PM2 = 4,
PX4_MFT_ETHERNET = 5,
PX4_MFT_T1_ETH = 6,
PX4_MFT_T100_ETH = 7,
PX4_MFT_T1000_ETH = 8,
} px4_hw_mft_item_id_t; } px4_hw_mft_item_id_t;
typedef int (*system_query_func_t)(const char *sub, const char *val, void *out);
#define PX4_MFT_MFT_TYPES { \
PX4_MFT_PX4IO, \
PX4_MFT_USB, \
PX4_MFT_CAN2, \
PX4_MFT_CAN3, \
PX4_MFT_PM2, \
PX4_MFT_ETHERNET, \
PX4_MFT_T1_ETH, \
PX4_MFT_T100_ETH, \
PX4_MFT_T1000_ETH }
#define PX4_MFT_MFT_STR_TYPES { \
"MFT_PX4IO", \
"MFT_USB", \
"MFT_CAN2", \
"MFT_CAN3", \
"MFT_PM2", \
"MFT_ETHERNET", \
"MFT_T1_ETH", \
"MFT_T100_ETH", \
"MFT_T1000_ETH", \
"MFT_T1000_ETH"}
typedef enum { typedef enum {
px4_hw_con_unknown = 0, px4_hw_con_unknown = 0,
px4_hw_con_onboard = 1, px4_hw_con_onboard = 1,
px4_hw_con_connector = 3, px4_hw_con_connector = 3,
} px4_hw_connection_t; } px4_hw_connection_t;
typedef struct { typedef struct {
unsigned int id: 16; /* The id px4_hw_mft_item_id_t */
unsigned int present: 1; /* 1 if this board have this item */ unsigned int present: 1; /* 1 if this board have this item */
unsigned int mandatory: 1; /* 1 if this item has to be present and working */ unsigned int mandatory: 1; /* 1 if this item has to be present and working */
unsigned int connection: 2; /* See px4_hw_connection_t */ unsigned int connection: 2; /* See px4_hw_connection_t */
@ -677,7 +722,7 @@ typedef const px4_hw_mft_item_t *px4_hw_mft_item;
#if defined(BOARD_HAS_VERSIONING) #if defined(BOARD_HAS_VERSIONING)
__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id); __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id);
__EXPORT int system_query_manifest(const char *sub, const char *val, void *out);
# define PX4_MFT_HW_SUPPORTED(ID) (board_query_manifest((ID))->present) # define PX4_MFT_HW_SUPPORTED(ID) (board_query_manifest((ID))->present)
# define PX4_MFT_HW_REQUIRED(ID) (board_query_manifest((ID))->mandatory) # define PX4_MFT_HW_REQUIRED(ID) (board_query_manifest((ID))->mandatory)
# define PX4_MFT_HW_IS_ONBOARD(ID) (board_query_manifest((ID))->connection == px4_hw_con_onboard) # define PX4_MFT_HW_IS_ONBOARD(ID) (board_query_manifest((ID))->connection == px4_hw_con_onboard)
@ -750,6 +795,26 @@ __EXPORT const char *board_get_hw_type_name(void);
#define board_get_hw_type_name() "" #define board_get_hw_type_name() ""
#endif #endif
/************************************************************************************
* Name: board_get_hw_base_type_name
*
* Description:
* Optional returns a 0 terminated string defining the HW type.
*
* Input Parameters:
* None
*
* Returned Value:
* a 0 terminated string defining the HW type. This may be a 0 length string ""
*
************************************************************************************/
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
__EXPORT const char *board_get_hw_base_type_name(void);
#else
#define board_get_hw_base_type_name() ""
#endif
/************************************************************************************ /************************************************************************************
* Name: board_get_hw_version * Name: board_get_hw_version
* *

View File

@ -73,7 +73,11 @@ struct px4_spi_bus_t {
struct px4_spi_bus_all_hw_t { struct px4_spi_bus_all_hw_t {
px4_spi_bus_t buses[SPI_BUS_MAX_BUS_ITEMS]; px4_spi_bus_t buses[SPI_BUS_MAX_BUS_ITEMS];
int board_hw_version_revision{-1}; ///< 0=default, >0 for a specific revision (see board_get_hw_version & board_get_hw_revision), -1=unused #if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
hw_fmun_id_t board_hw_fmun_id {USHRT_MAX};
#else
int board_hw_version_revision {-1}; ///< 0=default, >0 for a specific revision (see board_get_hw_version & board_get_hw_revision), -1=unused
#endif
}; };
#if BOARD_NUM_SPI_CFG_HW_VERSIONS > 1 #if BOARD_NUM_SPI_CFG_HW_VERSIONS > 1

View File

@ -0,0 +1,404 @@
/****************************************************************************
*
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* 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 pab_manifest.c
*
* This module supplies the interface to the manifest of hardware that is
* optional and dependent on the HW_BASE_ID
*
* 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 <board_config.h>
#include <inttypes.h>
#include <stdbool.h>
#include <syslog.h>
#include "systemlib/px4_macros.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
typedef struct {
hw_base_id_t hw_base_id; /* The ID of the Base */
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 base board configuration
// The ids of those components is given by the enum (px4_hw_mft_item_id_t)
// declared in board_common.h
// BASE ID 0 Auterion vXx base board
static const px4_hw_mft_item_t base_configuration_0[] = {
{
.id = PX4_MFT_PX4IO,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_USB,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_CAN2,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_CAN3,
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
{
.id = PX4_MFT_PM2,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_ETHERNET,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_connector,
},
{
.id = PX4_MFT_T100_ETH,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_connector,
},
};
// BASE ID 1 vXx base without px4io
static const px4_hw_mft_item_t base_configuration_1[] = {
{
.id = PX4_MFT_PX4IO,
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
{
.id = PX4_MFT_USB,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_CAN2,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_CAN3,
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
{
.id = PX4_MFT_PM2,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_ETHERNET,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_connector,
},
{
.id = PX4_MFT_T100_ETH,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_connector,
},
};
// BASE ID 2 Modal AI Alaised to ID 0
// BASE ID 3 NXP T1 PHY
static const px4_hw_mft_item_t base_configuration_3[] = {
{
.id = PX4_MFT_PX4IO,
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
{
.id = PX4_MFT_USB,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_CAN2,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_CAN3,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_PM2,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_ETHERNET,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_connector,
},
{
.id = PX4_MFT_T1_ETH,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_connector,
},
};
// BASE ID 4 HB CM4 Alaised to ID 0
// BASE ID 5 HB min
static const px4_hw_mft_item_t base_configuration_5[] = {
{
.id = PX4_MFT_PX4IO,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_USB,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_CAN2,
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
{
.id = PX4_MFT_CAN3,
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
{
.id = PX4_MFT_ETHERNET,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_connector,
},
{
.id = PX4_MFT_T100_ETH,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_connector,
},
};
// BASE ID 6 Not allocated
// BASE ID 7 Read from EEPROM
// BASE ID 8 Skynode QS with USB - Alaised to ID 0
// BASE ID 9 Auterion Skynode base RC9 & older (no usb
static const px4_hw_mft_item_t base_configuration_9[] = {
{
.id = PX4_MFT_PX4IO,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_USB,
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
{
.id = PX4_MFT_CAN2,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_CAN3,
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
{
.id = PX4_MFT_PM2,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_PM2,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
{
.id = PX4_MFT_ETHERNET,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_connector,
},
{
.id = PX4_MFT_T100_ETH,
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
};
// BASE ID 10 Skynode QS no USB Alaised to ID 9
// BASE ID 16 Auterion Skynode RC10, RC11, RC12, RC13 Alaised to ID 0
static px4_hw_mft_list_entry_t mft_lists[] = {
// ver_rev
{HW_BASE_ID(0), base_configuration_0, arraySize(base_configuration_0)}, // std Base with PX4IO
{HW_BASE_ID(1), base_configuration_1, arraySize(base_configuration_1)}, // std Base No PX4IO
{HW_BASE_ID(2), base_configuration_0, arraySize(base_configuration_0)}, // CUAV Base
{HW_BASE_ID(3), base_configuration_3, arraySize(base_configuration_3)}, // NXP T1 PHY
{HW_BASE_ID(4), base_configuration_0, arraySize(base_configuration_0)}, // HB CM4 base
{HW_BASE_ID(5), base_configuration_5, arraySize(base_configuration_5)}, // HB Mini
{HW_BASE_ID(8), base_configuration_0, arraySize(base_configuration_0)}, // Auterion Skynode ver 8 Aliased to 0
{HW_BASE_ID(9), base_configuration_9, arraySize(base_configuration_9)}, // Auterion Skynode ver 9
{HW_BASE_ID(10), base_configuration_9, arraySize(base_configuration_9)}, // Auterion Skynode ver 10
{HW_BASE_ID(16), base_configuration_0, arraySize(base_configuration_0)}, // Auterion Skynode ver 16
};
/************************************************************************************
* Name: base_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) {
hw_base_id_t hw_base_id = GET_HW_BASE_ID();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
if (mft_lists[i].hw_base_id == hw_base_id) {
boards_manifest = &mft_lists[i];
break;
}
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
syslog(LOG_ERR, "[boot] Board %04" PRIx16 " is not supported!\n", hw_base_id);
}
}
px4_hw_mft_item rv = &device_unsupported;
if (boards_manifest != px4_hw_mft_list_uninitialized)
for (unsigned int ndx = 0; ndx < boards_manifest->entries; ndx++) {
if (boards_manifest->mft[ndx].id == id) {
rv = &boards_manifest->mft[id];
break;
}
}
return rv;
}
__EXPORT int system_query_manifest(const char *sub, const char *val, void *out)
{
static const char *keys[] = PX4_MFT_MFT_STR_TYPES;
static const px4_hw_mft_item_id_t item_ids[] = PX4_MFT_MFT_TYPES;
px4_hw_mft_item rv = &device_unsupported;
int id = -1;
int intval = atoi(val);
for (unsigned int k = 0; k < arraySize(keys); k++) {
if (!strcmp(keys[k], sub)) {
id = item_ids[k];
break;
}
}
if (id != -1) {
// In case we have to filter when a FMUM is mounted to a BASE
// For now just use the board
rv = board_query_manifest(id);
return rv->present == intval ? OK : -ENXIO;
}
return -ENOENT;
}
#endif

View File

@ -44,12 +44,26 @@
#if BOARD_NUM_SPI_CFG_HW_VERSIONS > 1 #if BOARD_NUM_SPI_CFG_HW_VERSIONS > 1
void px4_set_spi_buses_from_hw_version() void px4_set_spi_buses_from_hw_version()
{ {
#if defined(BOARD_HAS_SIMPLE_HW_VERSIONING) # if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
int hw_version_revision = board_get_hw_version(); int hw_fmun_id = GET_HW_FMUM_ID();
#else
int hw_version_revision = HW_VER_REV(board_get_hw_version(), board_get_hw_revision());
#endif
for (int i = 0; i < BOARD_NUM_SPI_CFG_HW_VERSIONS; ++i) {
if (!px4_spi_buses && px4_spi_buses_all_hw[i].board_hw_fmun_id == 0) {
px4_spi_buses = px4_spi_buses_all_hw[i].buses;
}
if (px4_spi_buses_all_hw[i].board_hw_fmun_id == hw_fmun_id) {
px4_spi_buses = px4_spi_buses_all_hw[i].buses;
}
}
# else
# if defined(BOARD_HAS_SIMPLE_HW_VERSIONING)
int hw_version_revision = board_get_hw_version();
# else
int hw_version_revision = HW_VER_REV(board_get_hw_version(), board_get_hw_revision());
# endif
for (int i = 0; i < BOARD_NUM_SPI_CFG_HW_VERSIONS; ++i) { for (int i = 0; i < BOARD_NUM_SPI_CFG_HW_VERSIONS; ++i) {
if (!px4_spi_buses && px4_spi_buses_all_hw[i].board_hw_version_revision == 0) { if (!px4_spi_buses && px4_spi_buses_all_hw[i].board_hw_version_revision == 0) {
@ -61,6 +75,8 @@ void px4_set_spi_buses_from_hw_version()
} }
} }
# endif
if (!px4_spi_buses) { // fallback if (!px4_spi_buses) { // fallback
px4_spi_buses = px4_spi_buses_all_hw[0].buses; px4_spi_buses = px4_spi_buses_all_hw[0].buses;
} }

@ -1 +1 @@
Subproject commit 3f77354c0dc88793a47ff3b57595195ab45f7ba9 Subproject commit de41e7feaeffaec3ce65327e9569e8fdb553ca3d

View File

@ -36,6 +36,10 @@
__BEGIN_DECLS __BEGIN_DECLS
#define HW_INFO_SUFFIX "%0" STRINGIFY(HW_INFO_VER_DIGITS) "x%0" STRINGIFY(HW_INFO_REV_DIGITS) "x" #define HW_INFO_SUFFIX "%0" STRINGIFY(HW_INFO_VER_DIGITS) "x%0" STRINGIFY(HW_INFO_REV_DIGITS) "x"
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
# define HW_INFO_FMUM_SUFFIX "%0" STRINGIFY(HW_INFO_REV_DIGITS) "x"
# define HW_INFO_BASE_SUFFIX "%0" STRINGIFY(HW_INFO_VER_DIGITS) "x"
#endif
/************************************************************************************ /************************************************************************************
* Name: board_determine_hw_info * Name: board_determine_hw_info
* *

View File

@ -104,6 +104,13 @@ __EXPORT int px4_mft_query(const px4_mft_s *mft, px4_manifest_types_e type,
break; break;
case MFT: case MFT:
if (mft->mfts[m]->pmft != nullptr) {
system_query_func_t query = (system_query_func_t) mft->mfts[m]->pmft;
return query(sub, val, nullptr);
}
break;
default: default:
rv = -ENODATA; rv = -ENODATA;
break; break;

View File

@ -38,144 +38,76 @@
#include <nuttx/analog/adc.h> #include <nuttx/analog/adc.h>
#include <hardware/s32k1xx_sim.h> #include <hardware/s32k3xx_adc.h>
#include <hardware/s32k344_pinmux.h>
//todo S32K add ADC fior now steal the kinetis one
#include <kinetis.h>
#include <hardware/kinetis_adc.h>
#define _REG(_addr) (*(volatile uint32_t *)(_addr))
/* ADC register accessors */
#define REG(a, _reg) _REG(KINETIS_ADC##a##_BASE + (_reg))
#define rSC1A(adc) REG(adc, KINETIS_ADC_SC1A_OFFSET) /* ADC status and control registers 1 */
#define rSC1B(adc) REG(adc, KINETIS_ADC_SC1B_OFFSET) /* ADC status and control registers 1 */
#define rCFG1(adc) REG(adc, KINETIS_ADC_CFG1_OFFSET) /* ADC configuration register 1 */
#define rCFG2(adc) REG(adc, KINETIS_ADC_CFG2_OFFSET) /* Configuration register 2 */
#define rRA(adc) REG(adc, KINETIS_ADC_RA_OFFSET) /* ADC data result register */
#define rRB(adc) REG(adc, KINETIS_ADC_RB_OFFSET) /* ADC data result register */
#define rCV1(adc) REG(adc, KINETIS_ADC_CV1_OFFSET) /* Compare value registers */
#define rCV2(adc) REG(adc, KINETIS_ADC_CV2_OFFSET) /* Compare value registers */
#define rSC2(adc) REG(adc, KINETIS_ADC_SC2_OFFSET) /* Status and control register 2 */
#define rSC3(adc) REG(adc, KINETIS_ADC_SC3_OFFSET) /* Status and control register 3 */
#define rOFS(adc) REG(adc, KINETIS_ADC_OFS_OFFSET) /* ADC offset correction register */
#define rPG(adc) REG(adc, KINETIS_ADC_PG_OFFSET) /* ADC plus-side gain register */
#define rMG(adc) REG(adc, KINETIS_ADC_MG_OFFSET) /* ADC minus-side gain register */
#define rCLPD(adc) REG(adc, KINETIS_ADC_CLPD_OFFSET) /* ADC plus-side general calibration value register */
#define rCLPS(adc) REG(adc, KINETIS_ADC_CLPS_OFFSET) /* ADC plus-side general calibration value register */
#define rCLP4(adc) REG(adc, KINETIS_ADC_CLP4_OFFSET) /* ADC plus-side general calibration value register */
#define rCLP3(adc) REG(adc, KINETIS_ADC_CLP3_OFFSET) /* ADC plus-side general calibration value register */
#define rCLP2(adc) REG(adc, KINETIS_ADC_CLP2_OFFSET) /* ADC plus-side general calibration value register */
#define rCLP1(adc) REG(adc, KINETIS_ADC_CLP1_OFFSET) /* ADC plus-side general calibration value register */
#define rCLP0(adc) REG(adc, KINETIS_ADC_CLP0_OFFSET) /* ADC plus-side general calibration value register */
#define rCLMD(adc) REG(adc, KINETIS_ADC_CLMD_OFFSET) /* ADC minus-side general calibration value register */
#define rCLMS(adc) REG(adc, KINETIS_ADC_CLMS_OFFSET) /* ADC minus-side general calibration value register */
#define rCLM4(adc) REG(adc, KINETIS_ADC_CLM4_OFFSET) /* ADC minus-side general calibration value register */
#define rCLM3(adc) REG(adc, KINETIS_ADC_CLM3_OFFSET) /* ADC minus-side general calibration value register */
#define rCLM2(adc) REG(adc, KINETIS_ADC_CLM2_OFFSET) /* ADC minus-side general calibration value register */
#define rCLM1(adc) REG(adc, KINETIS_ADC_CLM1_OFFSET) /* ADC minus-side general calibration value register */
#define rCLM0(adc) REG(adc, KINETIS_ADC_CLM0_OFFSET) /* ADC minus-side general calibration value register */
int px4_arch_adc_init(uint32_t base_address) int px4_arch_adc_init(uint32_t base_address)
{ {
/* Input is Buss Clock 56 Mhz We will use /8 for 7 Mhz */ uint32_t regval;
irqstate_t flags = px4_enter_critical_section(); /* Configure and perform calibration */
putreg32(ADC_MCR_ADCLKSEL_DIV4, S32K3XX_ADC2_MCR);
_REG(KINETIS_SIM_SCGC3) |= SIM_SCGC3_ADC1; regval = getreg32(S32K3XX_ADC2_AMSIO);
rCFG1(1) = ADC_CFG1_ADICLK_BUSCLK | ADC_CFG1_MODE_1213BIT | ADC_CFG1_ADIV_DIV8; regval |= ADC_AMSIO_HSEN_MASK;
rCFG2(1) = 0; putreg32(regval, S32K3XX_ADC2_AMSIO);
rSC2(1) = ADC_SC2_REFSEL_DEFAULT;
px4_leave_critical_section(flags); regval = getreg32(S32K3XX_ADC2_CAL2);
regval &= ~ADC_CAL2_ENX;
putreg32(regval, S32K3XX_ADC2_CAL2);
/* Clear the CALF and begin the calibration */ regval = getreg32(S32K3XX_ADC2_CALBISTREG);
regval &= ~(ADC_CALBISTREG_TEST_EN | ADC_CALBISTREG_AVG_EN | ADC_CALBISTREG_NR_SMPL_MASK |
ADC_CALBISTREG_CALSTFUL | ADC_CALBISTREG_TSAMP_MASK | ADC_CALBISTREG_RESN_MASK);
regval |= ADC_CALBISTREG_TEST_EN | ADC_CALBISTREG_AVG_EN | ADC_CALBISTREG_NR_SMPL_4SMPL |
ADC_CALBISTREG_CALSTFUL | ADC_CALBISTREG_RESN_14BIT;
putreg32(regval, S32K3XX_ADC2_CALBISTREG);
rSC3(1) = ADC_SC3_CAL | ADC_SC3_CALF; while (getreg32(S32K3XX_ADC2_CALBISTREG) & ADC_CALBISTREG_C_T_BUSY) {};
while ((rSC1A(1) & ADC_SC1_COCO) == 0) { putreg32(ADC_MCR_PWDN, S32K3XX_ADC2_MCR);
usleep(100);
if (rSC3(1) & ADC_SC3_CALF) { putreg32(22, S32K3XX_ADC2_CTR0);
return -1;
}
}
/* dummy read to clear COCO of calibration */ putreg32(22, S32K3XX_ADC2_CTR1);
int32_t r = rRA(1); putreg32(0, S32K3XX_ADC2_DMAE);
/* Check the state of CALF at the end of calibration */ putreg32(ADC_MCR_ADCLKSEL_DIV4 | ADC_MCR_AVGS_32CONV | ADC_MCR_AVGEN | ADC_MCR_BCTU_MODE | ADC_MCR_MODE,
S32K3XX_ADC2_MCR);
if (rSC3(1) & ADC_SC3_CALF) { putreg32(0x10, S32K3XX_ADC2_NCMR0);
return -1;
}
/* Calculate the calibration values for single ended positive */ putreg32(0x10, S32K3XX_ADC2_NCMR1);
r = rCLP0(1) + rCLP1(1) + rCLP2(1) + rCLP3(1) + rCLP4(1) + rCLPS(1) ; regval = getreg32(S32K3XX_ADC2_MCR);
r = 0x8000U | (r >> 1U);
rPG(1) = r;
/* Calculate the calibration values for double ended Negitive */ regval |= ADC_MCR_NSTART;
r = rCLM0(1) + rCLM1(1) + rCLM2(1) + rCLM3(1) + rCLM4(1) + rCLMS(1) ; putreg32(regval, S32K3XX_ADC2_MCR);
r = 0x8000U | (r >> 1U);
rMG(1) = r;
/* kick off a sample and wait for it to complete */
hrt_abstime now = hrt_absolute_time();
rSC1A(1) = ADC_SC1_ADCH(ADC_SC1_ADCH_TEMP);
while (!(rSC1A(1) & ADC_SC1_COCO)) {
/* don't wait for more than 500us, since that means something broke - should reset here if we see this */
if ((hrt_absolute_time() - now) > 500) {
return -1;
}
}
return 0; return 0;
} }
void px4_arch_adc_uninit(uint32_t base_address) void px4_arch_adc_uninit(uint32_t base_address)
{ {
irqstate_t flags = px4_enter_critical_section();
_REG(KINETIS_SIM_SCGC3) &= ~SIM_SCGC3_ADC1;
px4_leave_critical_section(flags);
} }
uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel) uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel)
{ {
irqstate_t flags = px4_enter_critical_section(); uint32_t result = 0;
/* clear any previous COCC */ if (channel == 0) {
rRA(1); result = getreg32(S32K3XX_ADC2_PCDR4);
/* run a single conversion right now - should take about 35 cycles (5 microseconds) max */ if ((result & ADC_PCDR_VALID) == ADC_PCDR_VALID) {
rSC1A(1) = ADC_SC1_ADCH(channel); result = result & 0xFFFF;
/* wait for the conversion to complete */ } else {
const hrt_abstime now = hrt_absolute_time(); result = 0;
while (!(rSC1A(1) & ADC_SC1_COCO)) {
/* don't wait for more than 10us, since that means something broke - should reset here if we see this */
if ((hrt_absolute_time() - now) > 10) {
px4_leave_critical_section(flags);
return 0xffff;
} }
} }
/* read the result and clear EOC */
uint32_t result = rRA(1);
px4_leave_critical_section(flags);
return result; return result;
} }
@ -186,10 +118,10 @@ float px4_arch_adc_reference_v()
uint32_t px4_arch_adc_temp_sensor_mask() uint32_t px4_arch_adc_temp_sensor_mask()
{ {
return 1 << (ADC_SC1_ADCH_TEMP >> ADC_SC1_ADCH_SHIFT); return 0; // No temp sensor
} }
uint32_t px4_arch_adc_dn_fullcount() uint32_t px4_arch_adc_dn_fullcount()
{ {
return 1 << 12; // 12 bit ADC return 1 << 15; // 15 bit conversion data
} }

View File

@ -51,7 +51,7 @@
#include <lib/crc/crc.h> #include <lib/crc/crc.h>
#include <lib/systemlib/px4_macros.h> #include <lib/systemlib/px4_macros.h>
#if defined(BOARD_HAS_HW_VERSIONING) #if defined(BOARD_HAS_HW_VERSIONING) || defined(BOARD_HAS_HW_SPLIT_VERSIONING)
# if defined(GPIO_HW_VER_REV_DRIVE) # if defined(GPIO_HW_VER_REV_DRIVE)
# define GPIO_HW_REV_DRIVE GPIO_HW_VER_REV_DRIVE # define GPIO_HW_REV_DRIVE GPIO_HW_VER_REV_DRIVE
@ -67,7 +67,9 @@
static int hw_version = 0; static int hw_version = 0;
static int hw_revision = 0; static int hw_revision = 0;
static char hw_info[HW_INFO_SIZE] = {0}; static char hw_info[HW_INFO_SIZE] = {0};
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
static char hw_base_info[HW_INFO_SIZE] = {0};
#endif
/**************************************************************************** /****************************************************************************
* Protected Functions * Protected Functions
****************************************************************************/ ****************************************************************************/
@ -366,6 +368,27 @@ __EXPORT const char *board_get_hw_type_name()
return (const char *) hw_info; return (const char *) hw_info;
} }
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
/************************************************************************************
* Name: board_get_hw_base_type_name
*
* Description:
* Optional returns a 0 terminated string defining the base type.
*
* Input Parameters:
* None
*
* Returned Value:
* a 0 terminated string defining the HW type. This my be a 0 length string ""
*
************************************************************************************/
__EXPORT const char *board_get_hw_base_type_name()
{
return (const char *) hw_base_info;
}
#endif
/************************************************************************************ /************************************************************************************
* Name: board_get_hw_version * Name: board_get_hw_version
* *
@ -467,7 +490,12 @@ int board_determine_hw_info()
} }
if (rv == OK) { if (rv == OK) {
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
snprintf(hw_info, sizeof(hw_info), HW_INFO_INIT_PREFIX HW_INFO_FMUM_SUFFIX, GET_HW_FMUM_ID());
snprintf(hw_base_info, sizeof(hw_info), HW_INFO_BASE_SUFFIX, GET_HW_BASE_ID());
#else
snprintf(hw_info, sizeof(hw_info), HW_INFO_INIT_PREFIX HW_INFO_SUFFIX, hw_version, hw_revision); snprintf(hw_info, sizeof(hw_info), HW_INFO_INIT_PREFIX HW_INFO_SUFFIX, hw_version, hw_revision);
#endif
} }
return rv; return rv;

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