Compare commits

...

96 Commits

Author SHA1 Message Date
Daniel Agar dd58bd6df2 new INA231 power_monitor driver 2022-05-20 15:42:14 -04:00
Julian Oes 33a77c225c commander: lockdown is not termination
We use lockdown to prevent outputs like motors and servos from being
active in HITL simulation. This means that we can't treat the lockdown
flag as a flight_terminated, otherwise we can't arm in HITL at all.
2022-05-20 09:43:32 -04:00
Nicolas MARTIN a0cb7f6258 HITL: undefined time_remaining_s should be NAN 2022-05-20 09:38:43 -04:00
Nico van Duijn 04071b9456 Commander: ignore MAV_CMD_REQUEST_MSG
This commit adds the MAV_CMD_REQUEST_MESSAGE to the list of vehicle
commands which are ignored without generating a warning sound.
2022-05-20 15:36:42 +02:00
Matthias Grob 38e027ee45 ArmStateMachine: remove dependency on armed.armed
To have the internal state as single source of truth
for the arming state within Commander.
2022-05-20 13:51:51 +02:00
Matthias Grob 37c485ce89 ArmStateMachine: move arm state into the class 2022-05-20 13:51:51 +02:00
Matthias Grob 47532ca07b ArmStateMachine: replace state name array with method 2022-05-20 13:51:51 +02:00
alessandro c5bbf4553b ubuntu.sh: fix gazebo and openjdk for 22.04 2022-05-20 06:38:09 +02:00
Matthias Grob 887fe7dba2 commander_params: shorten low battery action delay
I got multiple times the feedback now that a consistent delay
is helpful and makes sense but the default delay
is too long
for low battery action where you're trying to come back in time
and possibly the emergency reaction kicks in while the critical action
is executing which leads to a longer accumulated delay.
2022-05-19 21:54:09 +02:00
Daniel Agar fd4b62032e commander: publish actuator_armed first on any change 2022-05-19 12:47:50 -04:00
PX4 BuildBot 9518b65f93 Update submodule mavlink to latest Thu May 19 00:38:59 UTC 2022
- mavlink in PX4/Firmware (87c73145b36a835b1635de0498a5613a7af5cafc): https://github.com/mavlink/mavlink/commit/a1cb2c0e71f191f04da3d92d92db8702a7e91ff6
    - mavlink current upstream: https://github.com/mavlink/mavlink/commit/99e82cad70494903a23a67de08ff9cbb5918d8f3
    - Changes: https://github.com/mavlink/mavlink/compare/a1cb2c0e71f191f04da3d92d92db8702a7e91ff6...99e82cad70494903a23a67de08ff9cbb5918d8f3

    99e82cad 2022-05-19 Hamish Willee - Deprecated GPS_INJECT_DATA (#1842)
bf3df03d 2022-05-16 Hamish Willee - WIND_COV - accuracy units are m/s (#1844)
a73d4864 2022-05-11 Hamish Willee - development.xml FIGURE_EIGHT_EXECUTION_STATUS - add a note about it being set at lower rate (#1841)
2022-05-18 21:41:08 -04:00
mcsauder e8da98fd14 Add gyro clipping to mirror accel clipping monitoring instances. 2022-05-18 21:16:05 -04:00
mcsauder ea10eacb99 Replace EKF/common.h #defines with enums. 2022-05-18 09:25:19 -04:00
Silvan Fuhrer 8f2c84d36f VTOL paras: add min of 0.1 to transition times
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-18 10:01:04 +02:00
Silvan Fuhrer c29ca6c959 tailsitter: guard against division by 0
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-18 10:01:04 +02:00
Silvan Fuhrer 3cf07e1be5 VTOL: rename params _PTCH to _PITCH
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-18 10:01:04 +02:00
Silvan Fuhrer 7c5f0121a5 VTOL: remove some unsued variables
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-18 10:01:04 +02:00
Silvan Fuhrer 2b7efeacca vtol_vehicle_status: replace several status bools by single vehicle_vtol_state
Replace vtol_in_rw_mode, vtol_in_trans_mode, in_transition_to_fw by vehicle_vtol_state.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-18 10:01:04 +02:00
Silvan Fuhrer 635f64a2e5 Commander: remove permanent stabilization option for fixed-wing flight
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-18 10:01:04 +02:00
Silvan Fuhrer d8444df11c Set tailsitter flag via vehicle status
Removes the necessity of including vtol_type.h in other modules.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-18 10:01:04 +02:00
Silvan Fuhrer 7292ce483c VTOL: move to cpp params API
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-18 10:01:04 +02:00
Daniel Agar ff16131874 icm42670p run at full speed 2022-05-17 08:14:22 -07:00
Daniel Agar 83daf648ef drivers/imu/invensense/icm42670p: cleanup and small fixes 2022-05-17 08:14:22 -07:00
Peter van der Perk 3ea492b7a2 UCANS32K146 Fix CAN1 STB pin 2022-05-17 03:13:05 -07:00
Matthias Grob 02e11eddce mavlink_mission: add more specific information to the error message 2022-05-17 07:49:00 +02:00
Junwoo Hwang 146f0cafe0 Add get*Expo() functions to the Sticks library
To return Exponential Values, which is helpful for reducing the
sensitivity of the stick around the centered value (0), since it's
exponential curve.

Useful for user adjustment implementations, where accidentally touching the stick
wouldn't have so much effect when using the Exponential value, compared
to using the raw position value.
2022-05-16 23:55:05 +02:00
Matthias Grob 4bd2d4cf35 rc_update: add unit tests for mode slot
To verify RC mode switch and mode button functionality works as expected.
2022-05-16 14:37:29 +02:00
achim 3fe4c6e3f5 boards: matek h743-mini specify drivers to still fit to flash
- the code has become a bit bigger again that now the drivers have to be specified a bit more precisely to still fit into the flash.
2022-05-13 14:05:04 -04:00
Beat Küng 32df76ca8a dshot: handle DSHOT_MIN for reversible outputs
Also ensures there's no deadband if dead_l == dead_h (the default).
2022-05-13 14:04:01 -04:00
Matthias Grob 57a0289627 trajectory_setpoint: correct comment typo "kinematically"
Co-authored-by: Mathieu Bresciani <brescianimathieu@gmail.com>
2022-05-12 17:19:48 +02:00
Matthias Grob 4017f4bb0b vehicle_local_position_setpoint: reorder fields for clarity 2022-05-12 17:19:48 +02:00
Matthias Grob b67fbac296 uuv_pos_control: siplify passing on trajectory position setpoint 2022-05-12 17:19:48 +02:00
Matthias Grob 200124f094 mavlink_receiver: check entire Vectors for NAN
Note: Behavioral change Inf also results in the flag being true.
2022-05-12 17:19:48 +02:00
Matthias Grob 8ca28f3796 Separate message for trajectory setpoint 2022-05-12 17:19:48 +02:00
Beat Küng 9166b6953d output drivers: init SmartLock after exit_and_cleanup
This fixes an invalid memory access when exiting the module:
exit_and_cleanup destroys the object, but lock_guard is destructed after
and accesses the lock.
2022-05-12 08:16:35 -04:00
Beat Küng 0a9378e0f6 mavsdk_tests: ensure motor is stopped for motor failure test 2022-05-12 07:58:56 +02:00
Alessandro Simovic b5a3c58a95 sitl: loosen some timeouts
The typhoon_h480 model would not always complete takeoff in 30 seconds
or finish the mission within 60 seconds.
2022-05-12 07:58:56 +02:00
Alessandro Simovic 5c1932dcca disable engine failure detector for SITL VTOL
Tried increasing ESC timeout for VTOL first

VTOL sitl tests are failing because the ESC telemetry seems to be coming
in at 0.3 Hz
2022-05-12 07:58:56 +02:00
Alessandro Simovic 06f69cd469 Add SITL tests for control allocation 2022-05-12 07:58:56 +02:00
Beat Küng 0f860045f7 failure_detector: add failure injector class for motor telemetry
This allows to test motor failures via 'failure motor off -i 1' on a real
system.
2022-05-12 07:58:56 +02:00
Alessandro Simovic 4640f395d7 simulator_mavlink: Add ESC telemetry 2022-05-12 07:58:56 +02:00
Alessandro Simovic 20ccfbb719 control_allocator: remove failed motor from effectiveness
- limit to handling only 1 motor failure
- Log which motor failures are handled
- Remove motor from effectiveness matrix without
  recomputing the scale / normalization
2022-05-12 07:58:56 +02:00
Alessandro Simovic fb71e7587c failure_detector: add motor/ESC failure detection 2022-05-12 07:58:56 +02:00
Beat Küng dfd934fbdb esc_report: add actuator_function 2022-05-12 07:58:56 +02:00
Hamish Willee aab2feb8f5 pwm.cpp: remove the test example (#19587) 2022-05-12 07:56:13 +02:00
alexklimaj 0f69f8ced8 Fix uavcan battery causing immediate RTL time remaining low 2022-05-11 21:48:12 -04:00
Daniel Agar fba7c972d1 drivers/rc_input: ensure RC inversion is disabled initially and latch RC_INPUT_PROTO conservatively
- this allows jumping straight to a non-SBUS RC protocol
 - increased the scan time per protocol 300->500 ms, which the newer DSM parser seems to need in some cases.
 - only set RC_INPUT_PROTO if we've had a successful RC lock for > 3 seconds
2022-05-11 14:30:41 -04:00
Daniel Agar c772e5230f commander: remove compile time dependencies on non-commander parameters
- this allows builds with mavlink fully disabled
 - move commander MAN_ARM_GESTURE, RC_MAP_ARM_SW, MC_AIRMODE checks to manual_control
2022-05-11 10:14:23 -04:00
Beat Küng 8d36ba6727 log_writer_file: fix corner case when mission log is enabled
Normally _should_run for mission is only ever true if _should_run for the
normal log is. There are exceptions though:
- the log buffer fails to allocate
- there was a write failure (e.g. due to SD card removal)
In that situation, the writer would not wait anymore but busy-loop.
2022-05-11 10:06:35 -04:00
Beat Küng ebbe08bc86 log_writer_file: protect access to _should_run, use px4::atomicbool for _exit_thread 2022-05-11 10:06:35 -04:00
Peter van der Perk 0053aeec97 Cyphal restore O1Heap statistics 2022-05-11 09:49:18 -04:00
Peter van der Perk e62e8b58d1 Update UCANS32K146 clocking to use XTAL and support higher pheriphal freq 2022-05-11 06:02:39 -07:00
Silvan Fuhrer ea2c1095c2 ROMFS: SITL tiltrotor: enable control allocaton and only tilt front motors
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-11 10:19:37 +02:00
Silvan Fuhrer 866f9fa95b Control Allocation: add option to disable yaw by differential thrust
This replaces the propeller_torque_disabled flag to disable yaw by differential thrust
for tiltrotor and tailsitter VTOLs, as propeller_torque_disabled is not enough to set
effectiveness of an acutator in the yaw axis to 0 in case it's tilted.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-11 10:19:37 +02:00
Silvan Fuhrer 46179586fb Control Allocation: Tiltrotor: pass only thrust magnitude instead of 3D thrust to allocator
Special case tiltrotor: instead of passing a 3D thrust vector (that would mostly have a x-component in FW, and z in
MC), pass the vector magnitude as z-component, plus the collective tilt. Passing 3D thrust plus tilt is not feasible as they
can't be allocated independently, and with the current controller it's not possible to have collective tilt calculated
by the allocator directly.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-11 10:19:37 +02:00
Daniel Agar a71d101869 ROMFS: delete 3037_parrot_disco_mod airframe 2022-05-10 16:23:20 -04:00
Daniel Agar 42d7fb0b66 ROMFS: delete 3035_viper airframe and mixer 2022-05-10 16:23:20 -04:00
Daniel Agar 61c5d11375 ROMFS: delete 3034_fx79 airframe 2022-05-10 16:23:20 -04:00
Daniel Agar f1a1ed4958 ROMFS: delete 3030_io_camflyer airframe 2022-05-10 16:23:20 -04:00
Daniel Agar b00d0720cd ROMFS: delete 13010_claire airframe 2022-05-10 16:23:20 -04:00
Daniel Agar 451cc5058d ROMFS: delete minimal DJI airframes 2022-05-10 16:23:20 -04:00
Daniel Agar fa1891ace2 ROMFS: delete steadidrone airframes 2022-05-10 16:23:20 -04:00
Daniel Agar af5e903b82 .vscode/.gitignore ignore all log files 2022-05-10 11:39:55 -04:00
Daniel Agar b77bb6d88d Makefile: bootloaders_update add all Matek targets 2022-05-10 11:39:54 -04:00
Daniel Agar 45e3fad3e0 Update submodule GPSDrivers to latest Tue May 10 12:38:49 UTC 2022
- GPSDrivers in PX4/Firmware (3ac8fdbe29): https://github.com/PX4/PX4-GPSDrivers/commit/6534b050ee1a48af7932c46a9a87277eed1cc997
    - GPSDrivers current upstream: https://github.com/PX4/PX4-GPSDrivers/commit/58968922b718176be8756f11113d16b2cfbc4022
    - Changes: https://github.com/PX4/PX4-GPSDrivers/compare/6534b050ee1a48af7932c46a9a87277eed1cc997...58968922b718176be8756f11113d16b2cfbc4022

    5896892 2022-04-26 Seppe Geuens - sbf: add heading support (#100)

Co-authored-by: PX4 BuildBot <bot@px4.io>
2022-05-10 11:38:52 -04:00
PX4 BuildBot 4b7b7dfa8d Update submodule mavlink to latest Tue May 10 12:39:00 UTC 2022
- mavlink in PX4/Firmware (d6dff7daa984514185a8f31f6e653a69a278ded8): https://github.com/mavlink/mavlink/commit/3b52eac09c2e37325e4bc49cd2667ea37bf1d7d2
    - mavlink current upstream: https://github.com/mavlink/mavlink/commit/a1cb2c0e71f191f04da3d92d92db8702a7e91ff6
    - Changes: https://github.com/mavlink/mavlink/compare/3b52eac09c2e37325e4bc49cd2667ea37bf1d7d2...a1cb2c0e71f191f04da3d92d92db8702a7e91ff6

    a1cb2c0e 2022-05-05 KonradRudin - Figure eight MAV_CMD (#1831)
0ebdf846 2022-04-28 Hamish Willee - common.xml: Deprecate MAV_CMD_GET_MESSAGE_INTERVAL for MAV_CMD_REQUEST_MESSAGE. (#1835)
f357fc78 2022-04-27 Hamish Willee - Deprecate MAV_CMD_GET_HOME_POSITION for MAV_CMD_REQUEST_MESSAGE (#1834)
2022-05-10 11:37:55 -04:00
Daniel Agar 371a551f05 github actions: add all matek targets and sort 2022-05-10 11:33:01 -04:00
Daniel Agar 73f4c3ea87 Jenkins: compile add all matek targets and sort 2022-05-10 11:32:52 -04:00
Daniel Agar 6d390f393c boards: matek_h743-mini_bootloader fix NuttX CONFIG_ARCH_BOARD_CUSTOM_DIR 2022-05-10 11:28:26 -04:00
Daniel Agar 5778553508 boards: matek_h743_bootloader fix NuttX CONFIG_ARCH_BOARD_CUSTOM_DIR 2022-05-10 11:26:15 -04:00
Daniel Agar a80a74af79 Jenkins: compile update uavcanv1 -> cyphal 2022-05-10 11:23:22 -04:00
Daniel Agar 858292209d boards: px4_fmu-v5_uavcanv0periph disable common differential pressure sensors to save flash 2022-05-10 11:17:24 -04:00
Peter van der Perk b1ad4e8864 Upgrade libcanard to 3.0 and rename uavcan_v1 to cyphal
Did some prep work for redundant interfaces by introducing CanardHandle class to decouple physical interfaces from cyphal.cpp
2022-05-10 09:46:18 -04:00
Beat Küng 3ac8fdbe29 px4/fmu-v5/stackcheck: disable module to reduce flash 2022-05-10 10:25:06 +02:00
Beat Küng 689ceefada px4/fmu-v2/fixedwing: disable module to reduce flash 2022-05-10 10:24:55 +02:00
Beat Küng fc062ffad4 omnibus/f4sd/ekf2: disable module to reduce flash 2022-05-10 10:24:43 +02:00
Konrad 0e464a91be Remove contradicting geofence parameter description
The flight termination action on geofence violation is described as only trigger, when the corresponding circuit breaker is not disabled. However, the description of the circuit breaker states, that the geofence action is not depedning on this circuit breaker. The implementation follows the description of the circuit breaker. Hence the GF_ACTION description is adapted.
2022-05-10 09:01:12 +02:00
Beat Küng 6a35c9f5fe px4/fmu-v5/protected.px4board: disable module to reduce flash 2022-05-10 08:57:39 +02:00
Beat Küng 639c5c741e px4/fmu-v2/multicopter.px4board: disable module to reduce flash 2022-05-10 08:57:39 +02:00
Beat Küng abb37a3d27 holybro/kakutef7: disable module to reduce flash 2022-05-10 08:57:39 +02:00
Beat Küng 5d114329d7 cubepilot/cubeorange/test.px4board: disable module to reduce flash 2022-05-10 08:57:39 +02:00
Beat Küng adc6472480 cuav/x7pro/test.px4board: disable module to reduce flash 2022-05-10 08:57:39 +02:00
Beat Küng 5cdb6fbd8e control_allocator: add helicopter mixer
Same logic as the existing mixer.
Untested.
2022-05-10 08:57:39 +02:00
Beat Küng 32402f31df control_allocator: increase max num motors to 12 2022-05-10 08:57:39 +02:00
Beat Küng 9f5c5591a2 ActuatorEffectivenessRotors: fix motor count check
Check during init to avoid out-of-bound access.
2022-05-10 08:57:39 +02:00
Daniel Agar 15296ab453 cmake: NuttX check that CONFIG_ARCH_BOARD_CUSTOM_DIR is in PX4_BOARD_DIR 2022-05-09 15:23:18 -04:00
Silvan Fuhrer 5d6c8c986d Commander: high wind speed handling updates
- add logic for detecting high wind speed in Commander,
and handle it toghether with wind speed warning
- trigger and enforce RTL if COM_WIND_MAX is breached

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-09 19:09:40 +02:00
Silvan Fuhrer 1aad82f87d Commander: add max flight time RTL
Adds COM_FLT_TIME_MAX param and logic in Commander to enforce RTL when
flight time is above this value. User can only override to LAND mode,
but not proceed flight beyond that.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
2022-05-09 19:09:40 +02:00
Daniel Agar 2e1cdc9e75 boards: modalai_fc-v1 enable dshot on all outputs 2022-05-09 11:31:31 -04:00
Igor Mišić ce4e9f6690 uavcan: use timer 6 by default on stm32f7 2022-05-06 19:45:53 -04:00
achim 9c12c2a152 boards: matek h743 update unified target 2022-05-06 14:57:37 -04:00
achim 76cf4332d9 boards: matek_h743-mini sync all Matek H743 boards 2022-05-06 14:56:20 -04:00
Thomas Stastny 90789be68f fw pos ctrl: turn back to takeoff point with npfg 2022-05-06 16:36:03 +02:00
Thomas Stastny 3ef5f433b5 fw pos ctrl: add missing guidance control interval setting to control_manual_position() 2022-05-06 16:36:03 +02:00
Thomas Stastny 1ab9fb22ee fw pos ctrl: fix state switching logic for takeoff and landing 2022-05-06 16:36:03 +02:00
Matthias Grob b3776134b8 Commander: ensure diconnected battery is cleared from bit field 2022-05-06 10:32:27 -04:00
299 changed files with 5527 additions and 3652 deletions
+9 -7
View File
@@ -61,18 +61,20 @@ pipeline {
"holybro_kakutef7_default",
"holybro_kakuteh7_default",
"holybro_pix32v5_default",
"matek_h743-slim",
"matek_gnss-m9n-f4_canbootloader",
"matek_gnss-m9n-f4_default",
"matek_h743-mini_default",
"matek_h743-slim_default",
"matek_h743_default",
"modalai_fc-v1_default",
"modalai_fc-v1_rtps",
"modalai_fc-v2_default",
"mro_ctrl-zero-f7_default",
"mro_ctrl-zero-f7-oem_default",
"mro_ctrl-zero-h7_default",
"mro_ctrl-zero-h7_rtps",
"mro_ctrl-zero-h7-oem_default",
"mro_ctrl-zero-h7-oem_rtps",
"mro_ctrl-zero-h7_default",
"mro_ctrl-zero-h7_rtps",
"mro_pixracerpro_default",
"mro_pixracerpro_rtps",
"mro_x21-777_default",
@@ -87,26 +89,26 @@ pipeline {
"nxp_ucans32k146_canbootloader",
"nxp_ucans32k146_default",
"omnibus_f4sd_default",
"raspberrypi_pico_default",
"px4_fmu-v2_default",
"px4_fmu-v2_fixedwing",
"px4_fmu-v2_lto",
"px4_fmu-v2_multicopter",
"px4_fmu-v2_rover",
"px4_fmu-v2_lto",
"px4_fmu-v3_default",
"px4_fmu-v4_default",
"px4_fmu-v4pro_default",
"px4_fmu-v5_cyphal",
"px4_fmu-v5_debug",
"px4_fmu-v5_default",
"px4_fmu-v5_lto",
"px4_fmu-v5_rtps",
"px4_fmu-v5_stackcheck",
"px4_fmu-v5_uavcanv0periph",
"px4_fmu-v5_uavcanv1",
"px4_fmu-v5_lto",
"px4_fmu-v5x_default",
"px4_fmu-v6u_default",
"px4_fmu-v6x_default",
"px4_io-v2_default",
"raspberrypi_pico_default",
"sky-drones_smartap-airlink_default",
"spracing_h7extreme_default",
"uvify_core_default"
+4 -2
View File
@@ -37,8 +37,10 @@ jobs:
holybro_kakutef7,
holybro_kakuteh7,
holybro_pix32v5,
matek_h743-slim,
matek_gnss-m9n-f4,
matek_h743,
matek_h743-mini,
matek_h743-slim,
modalai_fc-v1,
modalai_fc-v2,
mro_ctrl-zero-f7,
@@ -53,7 +55,6 @@ jobs:
nxp_fmurt1062-v1,
nxp_ucans32k146,
omnibus_f4sd,
raspberrypi_pico,
px4_fmu-v2,
px4_fmu-v3,
px4_fmu-v4,
@@ -62,6 +63,7 @@ jobs:
px4_fmu-v5x,
px4_fmu-v6u,
px4_fmu-v6x,
raspberrypi_pico,
sky-drones_smartap-airlink,
spracing_h7extreme,
uvify_core
+8 -8
View File
@@ -36,14 +36,14 @@
[submodule "Tools/jsbsim_bridge"]
path = Tools/jsbsim_bridge
url = https://github.com/PX4/px4-jsbsim-bridge.git
[submodule "src/drivers/uavcan_v1/libcanard"]
path = src/drivers/uavcan_v1/libcanard
url = https://github.com/UAVCAN/libcanard.git
[submodule "src/drivers/uavcan_v1/public_regulated_data_types"]
path = src/drivers/uavcan_v1/public_regulated_data_types
url = https://github.com/UAVCAN/public_regulated_data_types.git
[submodule "src/drivers/uavcan_v1/legacy_data_types"]
path = src/drivers/uavcan_v1/legacy_data_types
[submodule "src/drivers/cyphal/libcanard"]
path = src/drivers/cyphal/libcanard
url = https://github.com/opencyphal/libcanard.git
[submodule "src/drivers/cyphal/public_regulated_data_types"]
path = src/drivers/cyphal/public_regulated_data_types
url = https://github.com/opencyphal/public_regulated_data_types.git
[submodule "src/drivers/cyphal/legacy_data_types"]
path = src/drivers/cyphal/legacy_data_types
url = https://github.com/PX4/public_regulated_data_types.git
branch = legacy
[submodule "src/lib/crypto/monocypher"]
+2
View File
@@ -9,3 +9,5 @@ launch.json
ipch/
browse.vc.db*
*.log
+1 -1
View File
@@ -330,7 +330,7 @@ px4io_update: px4_io-v2_default cubepilot_io-v2_default
cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin
git status
bootloaders_update: cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-classic_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader
bootloaders_update: cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader matek_h743_bootloader matek_h743-mini_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-classic_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader
git status
.PHONY: coverity_scan
@@ -7,6 +7,11 @@
. ${R}etc/init.d/rc.vtol_defaults
# TODO: Enable motor failure detection when the
# VTOL no longer reports 0A for all ESCs in SITL
param set-default FD_ACT_EN 0
param set-default FD_ACT_MOT_TOUT 500
# param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 2
@@ -9,7 +9,7 @@
param set-default MAV_TYPE 21
# param set-default SYS_CTRL_ALLOC 1
param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 3
param set-default CA_ROTOR_COUNT 4
@@ -27,9 +27,7 @@ param set-default CA_ROTOR3_PY 0.1875
param set-default CA_ROTOR3_KM -0.05
param set-default CA_ROTOR0_TILT 1
param set-default CA_ROTOR1_TILT 2
param set-default CA_ROTOR2_TILT 3
param set-default CA_ROTOR3_TILT 4
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS0_TYPE 1
param set-default CA_SV_CS1_TRQ_R 0.5
@@ -1,6 +1,4 @@
mixer append /dev/pwm_output0 etc/mixers/mount_legs.aux.mix
mavlink start -x -u 14558 -r 4000 -f -m onboard -o 14530 -p
# shellcheck disable=SC2154
@@ -1,40 +0,0 @@
#!/bin/sh
#
# @name Steadidrone QU4D
#
# @type Quadrotor Wide
# @class Copter
#
# @output MAIN1 motor 1
# @output MAIN2 motor 2
# @output MAIN3 motor 3
# @output MAIN4 motor 4
# @output MAIN5 feed-through of RC AUX1 channel
# @output MAIN6 feed-through of RC AUX2 channel
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
# @output AUX4 feed-through of RC FLAPS channel
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set-default BAT1_N_CELLS 4
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_P 0.13
param set-default MC_ROLLRATE_I 0.05
param set-default MC_ROLLRATE_D 0.004
param set-default MC_PITCH_P 7
param set-default MC_PITCHRATE_P 0.19
param set-default MC_PITCHRATE_I 0.05
param set-default MC_PITCHRATE_D 0.004
param set-default MC_YAW_P 4
set MIXER quad_w
@@ -1,48 +0,0 @@
#!/bin/sh
#
# @name Steadidrone MAVRIK
#
# @type Octo Coax Wide
# @class Copter
#
# @output MAIN1 motor 1
# @output MAIN2 motor 2
# @output MAIN3 motor 3
# @output MAIN4 motor 4
# @output MAIN5 motor 5
# @output MAIN6 motor 6
# @output MAIN7 motor 7
# @output MAIN8 motor 8
#
# @maintainer Simon Wilks <simon@uaventure.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set-default MC_PITCH_P 4
param set-default MC_PITCHRATE_P 0.24
param set-default MC_PITCHRATE_I 0.09
param set-default MC_PITCHRATE_D 0.013
param set-default MC_PITCHRATE_MAX 180
param set-default MC_ROLL_P 4
param set-default MC_ROLLRATE_P 0.16
param set-default MC_ROLLRATE_I 0.07
param set-default MC_ROLLRATE_D 0.009
param set-default MC_ROLLRATE_MAX 180
param set-default MC_YAW_P 3
param set-default MPC_HOLD_MAX_XY 0.25
param set-default MPC_THR_MIN 0.15
param set-default MPC_Z_VEL_MAX_DN 2
param set-default BAT1_N_CELLS 4
set MIXER octo_cox_w
set PWM_OUT 12345678
@@ -1,37 +0,0 @@
#!/bin/sh
#
# @name CruiseAder Claire
#
# @type VTOL Tiltrotor
# @class VTOL
#
# @maintainer Samay Siga <samay_s@icloud.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 21
param set-default PWM_AUX_DISARM 1000
param set-default PWM_AUX_MAX 2000
param set-default PWM_AUX_MIN 1000
param set-default PWM_AUX_RATE 50
param set-default PWM_MAIN_MAX 2000
param set-default VT_MOT_ID 1234
param set-default VT_FW_MOT_OFFID 13
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TILT_FW 0.9
param set-default VT_TILT_MC 0.08
param set-default VT_TILT_TRANS 0.5
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_TYPE 1
set MIXER claire
set MIXER_AUX claire
set PWM_OUT 1234
@@ -131,7 +131,6 @@ param set-default VT_F_TRANS_DUR 1
param set-default VT_IDLE_PWM_MC 1025
param set-default VT_B_REV_OUT 0.5
param set-default VT_B_TRANS_THR 0.7
param set-default VT_FW_PERM_STAB 1
param set-default VT_TRANS_TIMEOUT 22
param set-default VT_F_TRANS_RAMP 4
@@ -1,45 +0,0 @@
#!/bin/sh
#
# @name IO Camflyer
#
# @type Flying Wing
# @class Plane
#
# @output MAIN1 left aileron
# @output MAIN2 right aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Simon Wilks <simon@uaventure.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.fw_defaults
param set-default FW_AIRSPD_MAX 15
param set-default FW_AIRSPD_TRIM 13
param set-default FW_R_TC 0.3
param set-default FW_P_TC 0.3
param set-default FW_L1_DAMPING 0.74
param set-default FW_L1_PERIOD 16
param set-default FW_LND_ANG 15
param set-default FW_LND_FLALT 5
param set-default FW_LND_HVIRT 13
param set-default FW_LND_TLALT 5
param set-default FW_THR_LND_MAX 0
param set-default FW_PR_FF 0.35
param set-default FW_RR_FF 0.6
param set-default FW_RR_P 0.04
param set-default PWM_MAIN_DISARM 1000
set MIXER fw_generic_wing
# Provide ESC a constant 1000 us pulse while disarmed
set PWM_OUT 4
@@ -1,29 +0,0 @@
#!/bin/sh
#
# @name FX-79 Buffalo Flying Wing
#
# @type Flying Wing
# @class Plane
#
# @output MAIN1 right aileron
# @output MAIN2 left aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Simon Wilks <simon@uaventure.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.fw_defaults
param set-default FW_AIRSPD_MAX 30
param set-default FW_AIRSPD_MIN 13
param set-default NAV_LOITER_RAD 150
set MIXER fw_generic_wing
@@ -1,23 +0,0 @@
#!/bin/sh
#
# @name Viper
#
# @type Flying Wing
# @class Plane
# @output MAIN1 left aileron
# @output MAIN2 right aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Simon Wilks <simon@uaventure.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.fw_defaults
set MIXER Viper
@@ -1,53 +0,0 @@
#!/bin/sh
#
# @name Modified Parrot Disco
#
# @url
#
# @type Flying Wing
# @class Plane
#
# @output MAIN1 left aileron
# @output MAIN2 right aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Jan Liphardt <JTLiphardt@gmail.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.fw_defaults
####################################
# Airspeed
####################################
param set-default FW_AIRSPD_MAX 27 # = 52 knots
####################################
# Pitch
####################################
# Pitch rate feed forward (def = 0.5 %/rad/sec)
param set-default FW_PR_FF 0.35
####################################
# Roll
####################################
# Basic limits (def = 50 deg)
param set-default FW_R_LIM 40
# Roll rate upper limit (def = 70 deg/s)
param set-default FW_R_RMAX 50
param set-default PWM_MAIN_DISARM 1000
set MIXER fw_generic_wing.main.mix
# Provide ESC a constant 1000 us pulse
set PWM_OUT 4
@@ -1,21 +0,0 @@
#!/bin/sh
#
# @name DJI F330 w/ DJI ESCs
#
# @type Quadrotor x
# @class Copter
#
# @maintainer Lorenz Meier <lorenz@px4.io>
# @board px4_fmu-v2 exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_I 0.05
param set-default MC_PITCH_P 7
param set-default MC_PITCHRATE_I 0.05
# DJI ESCs do not support calibration and need a higher min
param set-default PWM_MAIN_MIN 1230
@@ -1,20 +0,0 @@
#!/bin/sh
#
# @name DJI F450 w/ DJI ESCs
#
# @type Quadrotor x
# @class Copter
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
. ${R}etc/init.d/rc.mc_defaults
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_I 0.05
param set-default MC_PITCH_P 7
param set-default MC_PITCHRATE_I 0.05
param set-default MC_YAWRATE_P 0.3
# DJI ESCs do not support calibration and need a higher min
param set-default PWM_MAIN_MIN 1230
@@ -1,27 +0,0 @@
#!/bin/sh
#
# @name DJI Matrice 100
#
# @type Quadrotor x
# @class Copter
#
# @maintainer James Goppert <james.goppert@gmail.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set-default BAT1_N_CELLS 6
param set-default MC_ROLLRATE_P 0.05
param set-default MC_ROLLRATE_I 0.05
param set-default MC_ROLLRATE_D 0.001
param set-default MC_PITCHRATE_P 0.05
param set-default MC_PITCHRATE_I 0.05
param set-default MC_PITCHRATE_D 0.001
param set-default MC_YAWRATE_I 0
param set-default PWM_MAIN_MIN 1200
@@ -52,22 +52,16 @@ px4_add_romfs_files(
# [3000, 3999] Flying wing"
3000_generic_wing
3030_io_camflyer
3031_phantom
3032_skywalker_x5
3033_wingwing
3034_fx79
3035_viper
3036_pigeon
3037_parrot_disco_mod
3100_tbs_caipirinha
# [4000, 4999] Quadrotor x"
4001_quad_x
4003_qavr5
4009_qav250
4010_dji_f330
4011_dji_f450
4014_s500
4015_holybro_s500
4016_holybro_px4vision
@@ -81,7 +75,6 @@ px4_add_romfs_files(
4051_s250aq
4052_holybro_qav250
4053_holybro_kopis2
4060_dji_matrice_100
4061_atl_mantis_edu
4071_ifo
4072_draco
@@ -112,7 +105,6 @@ px4_add_romfs_files(
# [10000, 10999] Quadrotor Wide arm / H frame"
10015_tbs_discovery
10016_3dr_iris
10017_steadidrone_qu4d
10018_tbs_endurance
# [11000, 11999] Hexa Cox
@@ -120,7 +112,6 @@ px4_add_romfs_files(
# [12000, 12999] Octo Cox
12001_octo_cox
12002_steadidrone_mavrik
# [13000, 13999] VTOL
13000_generic_vtol_standard
@@ -133,7 +124,6 @@ px4_add_romfs_files(
13007_vtol_AAVVT_quad
13008_QuadRanger
13009_vtol_spt_ranger
13010_claire
13012_convergence
13013_deltaquad
13014_vtol_babyshark
+24
View File
@@ -181,6 +181,30 @@ then
pcf8583 start -X -a 0x51
fi
# INA226 digital power monitor
if param compare SENS_EN_INA226 1
then
ina226 -X start
fi
# INA228 digital power monitor
if param compare SENS_EN_INA228 1
then
ina228 -X start
fi
# INA231 digital power monitor
if param compare SENS_EN_INA231 1
then
ina231 -X start
fi
# INA238 digital power monitor
if param compare SENS_EN_INA238 1
then
ina238 -X start
fi
# probe for optional external I2C devices
if param compare SENS_EXT_I2C_PRB 1
then
+2 -2
View File
@@ -298,9 +298,9 @@ else
tune_control play error
fi
else
if param greater -s UAVCAN_V1_ENABLE 0
if param greater -s CYPHAL_ENABLE 0
then
uavcan_v1 start
cyphal start
fi
fi
@@ -40,8 +40,6 @@ px4_add_romfs_files(
babyshark.main.mix
blade130.main.mix
CCPM.main.mix
claire.aux.mix
claire.main.mix
cloudship.main.mix
coax.main.mix
delta.main.mix
@@ -83,7 +81,6 @@ px4_add_romfs_files(
tri_y_yaw-.main.mix
uuv_x.main.mix
vectored6dof.main.mix
Viper.main.mix
vtol_AAERT.aux.mix
vtol_AAVVT.aux.mix
vtol_TTTTAAER.aux.mix
-66
View File
@@ -1,66 +0,0 @@
Viper Delta-wing mixer
=================================
# @board px4_fmu-v2 exclude
Designed for Viper.
TODO (sjwilks): Add mixers for flaps.
This file defines mixers suitable for controlling a delta wing aircraft using
PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
assumed to be unused.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch) and 3 (thrust).
See the README for more information on the scaler format.
Elevon mixers
-------------
Three scalers total (output, roll, pitch).
On the assumption that the two elevon servos are physically reversed, the pitch
input is inverted between the two servos.
The scaling factor for roll inputs is adjusted to implement differential travel
for the elevons.
M: 2
S: 0 0 7500 7500 0 -10000 10000
S: 0 1 8000 8000 0 -10000 10000
M: 2
S: 0 0 7500 7500 0 -10000 10000
S: 0 1 -8000 -8000 0 -10000 10000
Output 2
--------
This mixer is empty.
Z:
Motor speed mixer
-----------------
Two scalers total (output, thrust).
This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
range. Inputs below zero are treated as zero.
M: 1
S: 0 3 0 20000 -10000 -10000 10000
Inputs to the mixer come from channel group 2 (payload), channels 0
(bay servo 1), 1 (bay servo 2) and 3 (drop release).
-----------------------------------------------------
M: 1
S: 2 0 10000 10000 0 -10000 10000
M: 1
S: 2 1 10000 10000 0 -10000 10000
M: 1
S: 2 2 -8000 -8000 0 -10000 10000
-28
View File
@@ -1,28 +0,0 @@
# mixer for the CruiseAder Claire tilt mechansim servo and elevons
=======================================================================
Tilt mechanism servo mixer
---------------------------
M: 1
S: 1 8 10000 10000 0 -10000 10000
Elevon mixers
-------------
M: 2
S: 1 0 7500 7500 0 -10000 10000
S: 1 1 7500 7500 0 -10000 10000
M: 2
S: 1 0 7500 7500 0 -10000 10000
S: 1 1 -7500 -7500 0 -10000 10000
@@ -1,8 +0,0 @@
# CruiseAder Claire Main Multirotor mixer for PX4FMU
# @board px4_fmu-v2 exclude
#
#===========================
R: 4x
+1 -2
View File
@@ -13,8 +13,7 @@ exec find boards msg src platforms test \
-path platforms/qurt/dspal -prune -o \
-path src/drivers/uavcan/libuavcan -prune -o \
-path src/drivers/uavcan/uavcan_drivers/kinetis/driver/include/uavcan_kinetis -prune -o \
-path src/drivers/uavcan_v1/libcanard -prune -o \
-path src/drivers/uavcannode_gps_demo/libcanard -prune -o \
-path src/drivers/cyphal/libcanard -prune -o \
-path src/lib/crypto/monocypher -prune -o \
-path src/lib/events/libevents -prune -o \
-path src/lib/parameters/uthash -prune -o \
+14 -5
View File
@@ -200,13 +200,12 @@ if [[ $INSTALL_SIM == "true" ]]; then
if [[ "${UBUNTU_RELEASE}" == "18.04" ]]; then
java_version=11
gazebo_version=9
elif [[ "${UBUNTU_RELEASE}" == "20.04" ]]; then
java_version=13
gazebo_version=11
elif [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then
java_version=11
else
java_version=14
gazebo_version=11
fi
# Java (jmavsim or fastrtps)
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
@@ -220,20 +219,30 @@ if [[ $INSTALL_SIM == "true" ]]; then
sudo update-alternatives --set java $(update-alternatives --list java | grep "java-$java_version")
# Gazebo
if [[ "${UBUNTU_RELEASE}" == "18.04" ]]; then
gazebo_version=9
gazebo_packages="gazebo$gazebo_version libgazebo$gazebo_version-dev"
elif [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then
gazebo_packages="gazebo libgazebo-dev"
else
# default and Ubuntu 20.04
gazebo_version=11
gazebo_packages="gazebo$gazebo_version libgazebo$gazebo_version-dev"
fi
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
# Update list, since new gazebo-stable.list has been added
sudo apt-get update -y --quiet
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
dmidecode \
gazebo$gazebo_version \
$gazebo_packages \
gstreamer1.0-plugins-bad \
gstreamer1.0-plugins-base \
gstreamer1.0-plugins-good \
gstreamer1.0-plugins-ugly \
gstreamer1.0-libav \
libeigen3-dev \
libgazebo$gazebo_version-dev \
libgstreamer-plugins-base1.0-dev \
libimage-exiftool-perl \
libopencv-dev \
+1
View File
@@ -4,6 +4,7 @@ CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_RPM=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
@@ -4,6 +4,7 @@ CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_RPM=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_EXAMPLES_FAKE_GPS=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
-1
View File
@@ -31,7 +31,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PWM=y
+29 -23
View File
@@ -6,32 +6,38 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_COMMON_BAROMETERS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_BAROMETER_DPS310=y
CONFIG_DRIVERS_CAMERA_CAPTURE=n
CONFIG_DRIVERS_CAMERA_TRIGGER=n
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42605=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_COMMON_DISTANCE_SENSOR=n
CONFIG_COMMON_LIGHT=n
CONFIG_COMMON_MAGNETOMETER=n
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PWM_OUT_SIM=n
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_RPM=y
CONFIG_DRIVERS_RPM=n
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_BOARD_UAVCAN_INTERFACES=1
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
@@ -43,42 +49,42 @@ CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VMOUNT=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_MODULES_GIMBAL=n
CONFIG_SYSTEMCMDS_BL_UPDATE=n
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_ESC_CALIB=y
CONFIG_SYSTEMCMDS_DUMPFILE=n
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=n
CONFIG_SYSTEMCMDS_MFT=n
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_MOTOR_TEST=n
CONFIG_SYSTEMCMDS_MTD=n
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PWM=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
CONFIG_SYSTEMCMDS_SD_BENCH=n
CONFIG_SYSTEMCMDS_SD_STRESS=n
CONFIG_SYSTEMCMDS_SERIAL_TEST=n
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=n
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=y
CONFIG_EXAMPLES_FAKE_GPS=n
Binary file not shown.
@@ -11,7 +11,7 @@
# CONFIG_STM32H7_SYSCFG is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/matek/h743-slim/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/matek/h743-mini/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
@@ -30,7 +30,7 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_PRODUCTID=0x004b
CONFIG_CDCACM_PRODUCTSTR="Matek H743-slim"
CONFIG_CDCACM_PRODUCTSTR="Matek H743-mini"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3162
@@ -51,7 +51,6 @@ CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_LIB_BOARDCTL=y
CONFIG_FS_PROCFS_MAX_TASKS=8
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_PREALLOC_TIMERS=50
@@ -284,17 +284,17 @@
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
/* 20 MHz Max for now - more reliable on some boards than 25 MHz
* 20 MHz = PLL1Q/(2*div), div = PLL1Q/(2*freq), div = 6 = 240 / 40
*/
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
# define STM32_SDMMC_MMCXFR_CLKDIV (6 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
# define STM32_SDMMC_SDXFR_CLKDIV (6 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
@@ -45,11 +45,11 @@ CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_PRODUCTID=0x0036
CONFIG_CDCACM_PRODUCTSTR="MatekH743-slim"
CONFIG_CDCACM_PRODUCTSTR="MatekH743-mini"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x1B8C
CONFIG_CDCACM_VENDORSTR="PX4"
CONFIG_CDCACM_VENDORSTR="Matek"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
@@ -86,7 +86,6 @@ CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MKFATFS_BUFFER_ALIGMENT=32
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
+2 -2
View File
@@ -120,8 +120,8 @@
/* PWM
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 10
#define DIRECT_INPUT_TIMER_CHANNELS 10
#define DIRECT_PWM_OUTPUT_CHANNELS 12
#define DIRECT_INPUT_TIMER_CHANNELS 12
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
+3 -3
View File
@@ -37,7 +37,7 @@ constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer3, DMA{DMA::Index1, DMA::Stream2, DMA::Channel5}),
initIOTimer(Timer::Timer5, DMA{DMA::Index1, DMA::Stream0, DMA::Channel6}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2}),
// initIOTimer(Timer::Timer15),
initIOTimer(Timer::Timer15),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
@@ -51,8 +51,8 @@ constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}),
// initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel1}, {GPIO::PortE, GPIO::Pin5}),
// initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel2}, {GPIO::PortE, GPIO::Pin6}),
initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel1}, {GPIO::PortE, GPIO::Pin5}),
initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel2}, {GPIO::PortE, GPIO::Pin6}),
};
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
+19 -4
View File
@@ -7,17 +7,22 @@ CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_DPS310=y
CONFIG_DRIVERS_CAMERA_CAPTURE=n
CONFIG_DRIVERS_CAMERA_TRIGGER=n
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42605=y
CONFIG_COMMON_LIGHT=n
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PWM_OUT_SIM=n
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_RPM=n
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
@@ -43,32 +48,42 @@ CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_MODULES_GIMBAL=n
CONFIG_SYSTEMCMDS_BL_UPDATE=n
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_ESC_CALIB=y
CONFIG_SYSTEMCMDS_DUMPFILE=n
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=n
CONFIG_SYSTEMCMDS_MFT=n
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_MOTOR_TEST=n
CONFIG_SYSTEMCMDS_MTD=n
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PWM=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
CONFIG_SYSTEMCMDS_SD_BENCH=n
CONFIG_SYSTEMCMDS_SD_STRESS=n
CONFIG_SYSTEMCMDS_SERIAL_TEST=n
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=n
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=n
BIN
View File
Binary file not shown.
@@ -11,7 +11,7 @@
# CONFIG_STM32H7_SYSCFG is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/matek/h743-slim/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/matek/h743/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
@@ -51,7 +51,6 @@ CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_LIB_BOARDCTL=y
CONFIG_FS_PROCFS_MAX_TASKS=8
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_PREALLOC_TIMERS=50
@@ -284,17 +284,17 @@
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
/* 20 MHz Max for now - more reliable on some boards than 25 MHz
* 20 MHz = PLL1Q/(2*div), div = PLL1Q/(2*freq), div = 6 = 240 / 40
*/
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
# define STM32_SDMMC_MMCXFR_CLKDIV (6 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
# define STM32_SDMMC_SDXFR_CLKDIV (6 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#else
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
#endif
+1 -1
View File
@@ -50,7 +50,7 @@ CONFIG_CDCACM_PRODUCTSTR="MatekH743"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x1B8C
CONFIG_CDCACM_VENDORSTR="PX4"
CONFIG_CDCACM_VENDORSTR="Matek"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
+2 -2
View File
@@ -120,8 +120,8 @@
/* PWM
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 10
#define DIRECT_INPUT_TIMER_CHANNELS 10
#define DIRECT_PWM_OUTPUT_CHANNELS 12
#define DIRECT_INPUT_TIMER_CHANNELS 12
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
+3 -3
View File
@@ -37,7 +37,7 @@ constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer3, DMA{DMA::Index1, DMA::Stream2, DMA::Channel5}),
initIOTimer(Timer::Timer5, DMA{DMA::Index1, DMA::Stream0, DMA::Channel6}),
initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2}),
// initIOTimer(Timer::Timer15),
initIOTimer(Timer::Timer15),
};
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
@@ -51,8 +51,8 @@ constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}),
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}),
// initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel1}, {GPIO::PortE, GPIO::Pin5}),
// initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel2}, {GPIO::PortE, GPIO::Pin6}),
initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel1}, {GPIO::PortE, GPIO::Pin5}),
initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel2}, {GPIO::PortE, GPIO::Pin6}),
};
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
+1 -1
View File
@@ -47,7 +47,7 @@
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
initIOTimer(Timer::Timer1, DMA{DMA::Index2, DMA::Stream5, DMA::Channel6}),
initIOTimer(Timer::Timer4),
initIOTimer(Timer::Timer4, DMA{DMA::Index1, DMA::Stream6, DMA::Channel2}),
};
+3 -3
View File
@@ -1,4 +1,4 @@
CONFIG_DRIVERS_UAVCAN=n
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER=y
CONFIG_DRIVERS_CYPHAL=y
CONFIG_CYPHAL_BMS_SUBSCRIBER=y
CONFIG_CYPHAL_UORB_SENSOR_GPS_SUBSCRIBER=y
+8 -8
View File
@@ -1,9 +1,9 @@
CONFIG_DRIVERS_UAVCAN=n
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
CONFIG_UAVCAN_V1_ESC_SUBSCRIBER=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_0=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_1=y
CONFIG_UAVCAN_V1_READINESS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER=y
CONFIG_DRIVERS_CYPHAL=y
CONFIG_CYPHAL_BMS_SUBSCRIBER=y
CONFIG_CYPHAL_ESC_SUBSCRIBER=y
CONFIG_CYPHAL_GNSS_SUBSCRIBER_0=y
CONFIG_CYPHAL_GNSS_SUBSCRIBER_1=y
CONFIG_CYPHAL_READINESS_PUBLISHER=y
CONFIG_CYPHAL_UORB_ACTUATOR_OUTPUTS_PUBLISHER=y
CONFIG_CYPHAL_UORB_SENSOR_GPS_SUBSCRIBER=y
+4 -4
View File
@@ -7,10 +7,10 @@ CONFIG_DRIVERS_BOOTLOADERS=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_CLIENT=y
CONFIG_UAVCAN_V1_APP_DESCRIPTOR=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER=y
CONFIG_DRIVERS_CYPHAL=y
CONFIG_CYPHAL_CLIENT=y
CONFIG_CYPHAL_APP_DESCRIPTOR=y
CONFIG_CYPHAL_UORB_SENSOR_GPS_PUBLISHER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
@@ -6,4 +6,4 @@
pwm_out mode_pwm1 start
ifup can0
uavcan_v1 start
cyphal start
+2
View File
@@ -159,10 +159,12 @@ int s32k1xx_bringup(void)
if (s32k1xx_gpioread(BOARD_REVISION_DETECT_PIN)) {
/* STB high -> active CAN phy */
s32k1xx_pinconfig(PIN_CAN0_STB | GPIO_OUTPUT_ONE);
s32k1xx_pinconfig(PIN_CAN1_STB | GPIO_OUTPUT_ONE);
} else {
/* STB low -> active CAN phy */
s32k1xx_pinconfig(PIN_CAN0_STB | GPIO_OUTPUT_ZERO);
s32k1xx_pinconfig(PIN_CAN1_STB | GPIO_OUTPUT_ZERO);
}
#endif
+1 -1
View File
@@ -110,7 +110,7 @@ const struct clock_configuration_s g_initial_clkconfig = {
{
.mode = SCG_SPLL_MONITOR_DISABLE, /* SPLLCM */
.div1 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SPLLDIV1 */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SPLLDIV2 */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_2, /* SPLLDIV2 */
.prediv = 1, /* PREDIV */
.mult = 40, /* MULT */
.src = 0, /* SOURCE */
+4 -4
View File
@@ -101,7 +101,7 @@ const struct peripheral_clock_config_s g_peripheral_clockconfig0[] = {
#else
.clkgate = false,
#endif
.clksrc = CLK_SRC_SIRC_DIV2,
.clksrc = CLK_SRC_SPLL_DIV2,
},
{
.clkname = LPSPI0_CLK,
@@ -110,7 +110,7 @@ const struct peripheral_clock_config_s g_peripheral_clockconfig0[] = {
#else
.clkgate = false,
#endif
.clksrc = CLK_SRC_SIRC_DIV2,
.clksrc = CLK_SRC_SPLL_DIV2,
},
{
.clkname = LPUART0_CLK,
@@ -119,7 +119,7 @@ const struct peripheral_clock_config_s g_peripheral_clockconfig0[] = {
#else
.clkgate = false,
#endif
.clksrc = CLK_SRC_SIRC_DIV2,
.clksrc = CLK_SRC_SPLL_DIV2,
},
{
.clkname = LPUART1_CLK,
@@ -128,7 +128,7 @@ const struct peripheral_clock_config_s g_peripheral_clockconfig0[] = {
#else
.clkgate = false,
#endif
.clksrc = CLK_SRC_SIRC_DIV2,
.clksrc = CLK_SRC_SPLL_DIV2,
},
{
.clkname = RTC0_CLK,
+1
View File
@@ -1,3 +1,4 @@
CONFIG_DRIVERS_OSD=n
CONFIG_DRIVERS_TELEMETRY_FRSKY_TELEMETRY=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_EKF2=y
-2
View File
@@ -7,9 +7,7 @@ CONFIG_SYSTEMCMDS_BL_UPDATE=n
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4525DO=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LL40LS=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_SYSTEMCMDS_PERF=y
-1
View File
@@ -1,3 +1,2 @@
CONFIG_SYSTEMCMDS_BL_UPDATE=n
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
@@ -2,6 +2,6 @@
CONFIG_DRIVERS_HEATER=n
CONFIG_DRIVERS_OSD=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER=y
CONFIG_CYPHAL_BMS_SUBSCRIBER=y
CONFIG_CYPHAL_UORB_SENSOR_GPS_SUBSCRIBER=y
CONFIG_DRIVERS_CYPHAL=y
+1
View File
@@ -21,6 +21,7 @@ CONFIG_MODULES_FW_POS_CONTROL=n
CONFIG_MODULES_FW_POS_CONTROL_L1=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_SIH=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_MODULES_UUV_ATT_CONTROL=n
CONFIG_MODULES_UUV_POS_CONTROL=n
CONFIG_MODULES_VTOL_ATT_CONTROL=n
+1
View File
@@ -4,6 +4,7 @@ CONFIG_COMMON_TELEMETRY=n
CONFIG_DRIVERS_BATT_SMBUS=n
CONFIG_DRIVERS_CAMERA_CAPTURE=n
CONFIG_DRIVERS_CAMERA_TRIGGER=n
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=n
CONFIG_DRIVERS_HEATER=n
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=n
@@ -1,4 +1,5 @@
# CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE is not set
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=n
CONFIG_COMMON_HYGROMETERS=n
CONFIG_COMMON_TELEMETRY=n
CONFIG_DRIVERS_ADC_ADS1115=n
+1
View File
@@ -33,6 +33,7 @@ CONFIG_DRIVERS_PCA9685=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA231=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_PWM_INPUT=y
CONFIG_DRIVERS_PWM_OUT=y
+1
View File
@@ -164,6 +164,7 @@ set(msg_files
timesync.msg
timesync_status.msg
trajectory_bezier.msg
trajectory_setpoint.msg
trajectory_waypoint.msg
transponder_report.msg
tune_control.msg
+6 -4
View File
@@ -4,7 +4,9 @@ uint64 timestamp_sample # the timestamp the data this control response is ba
uint16 reversible_flags # bitset which motors are configured to be reversible
uint8 NUM_CONTROLS = 8
float32[8] control # range: [-1, 1], where 1 means maximum positive thrust,
# -1 maximum negative (if not supported by the output, <0 maps to NaN),
# and NaN maps to disarmed (stop the motors)
uint8 ACTUATOR_FUNCTION_MOTOR1 = 101
uint8 NUM_CONTROLS = 12
float32[12] control # range: [-1, 1], where 1 means maximum positive thrust,
# -1 maximum negative (if not supported by the output, <0 maps to NaN),
# and NaN maps to disarmed (stop the motors)
+1 -1
View File
@@ -7,7 +7,7 @@ uint8 ACTION_RELEASE_CONTROL = 0 # exit test mode for the given function
uint8 ACTION_DO_CONTROL = 1 # enable actuator test mode
uint8 FUNCTION_MOTOR1 = 101
uint8 MAX_NUM_MOTORS = 8
uint8 MAX_NUM_MOTORS = 12
uint8 FUNCTION_SERVO1 = 201
uint8 MAX_NUM_SERVOS = 8
+2
View File
@@ -19,3 +19,5 @@ int8 ACTUATOR_SATURATION_LOWER = -2 # The actuator is saturated (with a valu
int8[16] actuator_saturation # Indicates actuator saturation status.
# Note 1: actuator saturation does not necessarily imply that the thrust setpoint or the torque setpoint were not achieved.
# Note 2: an actuator with limited dynamics can be indicated as upper-saturated even if it as not reached its maximum value.
uint16 handled_motor_failure_mask # Bitmask of failed motors that were removed from the allocation / effectiveness matrix. Not necessarily identical to the report from FailureDetector
+2
View File
@@ -8,6 +8,8 @@ uint8 esc_address # Address of current ESC (in most cases 1-8 / must be set
uint8 esc_state # State of ESC - depend on Vendor
uint8 actuator_function # actuator output function (one of Motor1...MotorN)
uint16 failures # Bitmask to indicate the internal ESC faults
uint8 FAILURE_OVER_CURRENT = 0 # (1 << 0)
+2 -1
View File
@@ -6,8 +6,9 @@ bool fd_pitch
bool fd_alt
bool fd_ext
bool fd_arm_escs
bool fd_high_wind
bool fd_battery
bool fd_imbalanced_prop
bool fd_motor
float32 imbalanced_prop_metric # Metric of the imbalanced propeller check (low-passed)
uint16 motor_failure_mask # Bit-mask with motor indices, indicating critical motor failures
+12 -10
View File
@@ -2,22 +2,24 @@
# These fields are scaled and offset-compensated where possible and do not
# change with board revisions and sensor updates.
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
int32 RELATIVE_TIMESTAMP_INVALID = 2147483647 # (0x7fffffff) If one of the relative timestamps is set to this value, it means the associated sensor values are invalid
int32 RELATIVE_TIMESTAMP_INVALID = 2147483647 # (0x7fffffff) If one of the relative timestamps is set to this value, it means the associated sensor values are invalid
# gyro timstamp is equal to the timestamp of the message
float32[3] gyro_rad # average angular rate measured in the FRD body frame XYZ-axis in rad/s over the last gyro sampling period
uint32 gyro_integral_dt # gyro measurement sampling period in microseconds
float32[3] gyro_rad # average angular rate measured in the FRD body frame XYZ-axis in rad/s over the last gyro sampling period
uint32 gyro_integral_dt # gyro measurement sampling period in microseconds
int32 accelerometer_timestamp_relative # timestamp + accelerometer_timestamp_relative = Accelerometer timestamp
float32[3] accelerometer_m_s2 # average value acceleration measured in the FRD body frame XYZ-axis in m/s^2 over the last accelerometer sampling period
uint32 accelerometer_integral_dt # accelerometer measurement sampling period in microseconds
int32 accelerometer_timestamp_relative # timestamp + accelerometer_timestamp_relative = Accelerometer timestamp
float32[3] accelerometer_m_s2 # average value acceleration measured in the FRD body frame XYZ-axis in m/s^2 over the last accelerometer sampling period
uint32 accelerometer_integral_dt # accelerometer measurement sampling period in microseconds
uint8 CLIPPING_X = 1
uint8 CLIPPING_Y = 2
uint8 CLIPPING_Z = 4
uint8 accelerometer_clipping # bitfield indicating if there was any accelerometer clipping (per axis) during the sampling period
uint8 accel_calibration_count # Calibration changed counter. Monotonically increases whenever accelermeter calibration changes.
uint8 gyro_calibration_count # Calibration changed counter. Monotonically increases whenever rate gyro calibration changes.
uint8 accelerometer_clipping # bitfield indicating if there was any accelerometer clipping (per axis) during the integration time frame
uint8 gyro_clipping # bitfield indicating if there was any gyro clipping (per axis) during the integration time frame
uint8 accel_calibration_count # Calibration changed counter. Monotonically increases whenever accelermeter calibration changes.
uint8 gyro_calibration_count # Calibration changed counter. Monotonically increases whenever rate gyro calibration changes.
+2
View File
@@ -11,6 +11,8 @@ float32 temperature # temperature in degrees Celsius
uint32 error_count
uint8[3] clip_counter # clip count per axis in the sample period
uint8 samples # number of raw samples that went into this message
uint8 ORB_QUEUE_LENGTH = 8
+1 -2
View File
@@ -59,8 +59,7 @@ rtps:
send: true
- msg: vehicle_local_position_setpoint
receive: true
- msg: trajectory_setpoint # multi-topic / alias of vehicle_local_position_setpoint
base: vehicle_local_position_setpoint
- msg: trajectory_setpoint
receive: true
- msg: vehicle_odometry
send: true
+15
View File
@@ -0,0 +1,15 @@
# Trajectory setpoint in NED frame
# Input to PID position controller.
# Needs to be kinematically consistent and feasible for smooth flight.
# setting a value to NaN means the state should not be controlled
uint64 timestamp # time since system start (microseconds)
# NED local world frame
float32[3] position # in meters
float32[3] velocity # in meters/second
float32[3] acceleration # in meters/second^2
float32[3] jerk # in meters/second^3 (for logging only)
float32 yaw # euler angle of desired attitude in radians -PI..+PI
float32 yawspeed # angular velocity around NED frame z-axis in radians/second
+5 -5
View File
@@ -1,12 +1,12 @@
# This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
float32[4] q # Quaternion rotation from the FRD body frame to the NED earth frame
float32[4] delta_q_reset # Amount by which quaternion has changed during last reset
uint8 quat_reset_counter # Quaternion reset counter
float32[4] q # Quaternion rotation from the FRD body frame to the NED earth frame
float32[4] delta_q_reset # Amount by which quaternion has changed during last reset
uint8 quat_reset_counter # Quaternion reset counter
# TOPICS vehicle_attitude vehicle_attitude_groundtruth vehicle_vision_attitude
# TOPICS estimator_attitude
+3
View File
@@ -8,12 +8,15 @@ uint32 gyro_device_id # Gyroscope unique device ID for the sensor that
float32[3] delta_angle # delta angle about the FRD body frame XYZ-axis in rad over the integration time frame (delta_angle_dt)
float32[3] delta_velocity # delta velocity in the FRD body frame XYZ-axis in m/s over the integration time frame (delta_velocity_dt)
uint16 delta_angle_dt # integration period in microseconds
uint16 delta_velocity_dt # integration period in microseconds
uint8 CLIPPING_X = 1
uint8 CLIPPING_Y = 2
uint8 CLIPPING_Z = 4
uint8 delta_angle_clipping # bitfield indicating if there was any gyro clipping (per axis) during the integration time frame
uint8 delta_velocity_clipping # bitfield indicating if there was any accelerometer clipping (per axis) during the integration time frame
uint8 accel_calibration_count # Calibration changed counter. Monotonically increases whenever accelermeter calibration changes.
+1
View File
@@ -4,6 +4,7 @@ uint32 accel_device_id # unique device ID for the sensor that does not
uint32 gyro_device_id # unique device ID for the sensor that does not change between power cycles
uint32[3] accel_clipping # total clipping per axis
uint32[3] gyro_clipping # total clipping per axis
uint32 accel_error_count
uint32 gyro_error_count
+6 -5
View File
@@ -1,18 +1,19 @@
# Local position setpoint in NED frame
# setting something to NaN means the state should not be controlled
# Telemetry of PID position controller to monitor tracking.
# NaN means the state was not controlled
uint64 timestamp # time since system start (microseconds)
float32 x # in meters NED
float32 y # in meters NED
float32 z # in meters NED
float32 yaw # in radians NED -PI..+PI
float32 yawspeed # in radians/sec
float32 vx # in meters/sec
float32 vy # in meters/sec
float32 vz # in meters/sec
float32[3] acceleration # in meters/sec^2
float32[3] jerk # in meters/sec^3
float32[3] thrust # normalized thrust vector in NED
# TOPICS vehicle_local_position_setpoint trajectory_setpoint
float32 yaw # in radians NED -PI..+PI
float32 yawspeed # in radians/sec
+12 -16
View File
@@ -1,5 +1,3 @@
# If you change the order, add or remove arming_state_t states make sure to update the arrays
# in state_machine_helper.cpp as well.
uint64 timestamp # time since system start (microseconds)
uint8 ARMING_STATE_INIT = 0
@@ -11,15 +9,15 @@ uint8 ARMING_STATE_IN_AIR_RESTORE = 5
uint8 ARMING_STATE_MAX = 6
# FailureDetector status
uint8 FAILURE_NONE = 0
uint8 FAILURE_ROLL = 1 # (1 << 0)
uint8 FAILURE_PITCH = 2 # (1 << 1)
uint8 FAILURE_ALT = 4 # (1 << 2)
uint8 FAILURE_EXT = 8 # (1 << 3)
uint8 FAILURE_ARM_ESC = 16 # (1 << 4)
uint8 FAILURE_HIGH_WIND = 32 # (1 << 5)
uint8 FAILURE_BATTERY = 64 # (1 << 6)
uint8 FAILURE_IMBALANCED_PROP = 128 # (1 << 7)
uint16 FAILURE_NONE = 0
uint16 FAILURE_ROLL = 1 # (1 << 0)
uint16 FAILURE_PITCH = 2 # (1 << 1)
uint16 FAILURE_ALT = 4 # (1 << 2)
uint16 FAILURE_EXT = 8 # (1 << 3)
uint16 FAILURE_ARM_ESC = 16 # (1 << 4)
uint16 FAILURE_BATTERY = 32 # (1 << 5)
uint16 FAILURE_IMBALANCED_PROP = 64 # (1 << 6)
uint16 FAILURE_MOTOR = 128 # (1 << 7)
# HIL
uint8 HIL_STATE_OFF = 0
@@ -32,7 +30,7 @@ uint8 NAVIGATION_STATE_POSCTL = 2 # Position control mode
uint8 NAVIGATION_STATE_AUTO_MISSION = 3 # Auto mission mode
uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode
uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode
uint8 NAVIGATION_STATE_AUTO_LANDENGFAIL = 8 # Auto land on engine failure
uint8 NAVIGATION_STATE_UNUSED3 = 8 # Free slot
uint8 NAVIGATION_STATE_UNUSED = 9 # Free slot
uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode
uint8 NAVIGATION_STATE_UNUSED1 = 11 # Free slot
@@ -69,13 +67,12 @@ uint8 system_type # system type, contains mavlink MAV_TYPE
uint8 system_id # system id, contains MAVLink's system ID field
uint8 component_id # subsystem / component id, contains MAVLink's component ID field
uint8 vehicle_type # Type of vehicle (fixed-wing, rotary wing, ground)
uint8 vehicle_type # Type of vehicle (rotary wing/fixed-wing/rover/airship, see above)
# If the vehicle is a VTOL, then this value will be VEHICLE_TYPE_ROTARY_WING while flying as a multicopter,
# and VEHICLE_TYPE_FIXED_WING when flying as a fixed-wing
bool is_vtol # True if the system is VTOL capable
bool is_vtol_tailsitter # True if the system performs a 90° pitch down rotation during transition from MC to FW
bool vtol_fw_permanent_stab # True if VTOL should stabilize attitude for fw in manual mode
bool in_transition_mode # True if VTOL is doing a transition
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
@@ -86,11 +83,10 @@ uint8 data_link_lost_counter # counts unique data link lost events
bool high_latency_data_link_lost # Set to true if the high latency data link (eg. RockBlock Iridium 9603 telemetry module) is lost
bool engine_failure # Set to true if an engine failure is detected
bool mission_failure # Set to true if mission could not continue/finish
bool geofence_violated
uint8 failure_detector_status # Bitmask containing FailureDetector status [0, 0, 0, 0, 0, FAILURE_ALT, FAILURE_PITCH, FAILURE_ROLL]
uint16 failure_detector_status # Bitmask containing FailureDetector status [0, 0, 0, 0, 0, FAILURE_ALT, FAILURE_PITCH, FAILURE_ROLL]
# see SYS_STATUS mavlink message for the following
# lower 32 bits are for the base flags, higher 32 bits are or the extended flags
-1
View File
@@ -28,7 +28,6 @@ bool flight_terminated
bool circuit_breaker_engaged_power_check
bool circuit_breaker_engaged_airspd_check
bool circuit_breaker_engaged_enginefailure_check
bool circuit_breaker_flight_termination_disabled
bool circuit_breaker_engaged_usb_check
bool circuit_breaker_engaged_posfailure_check # set to true when the position valid checks have been disabled
+2 -4
View File
@@ -7,8 +7,6 @@ uint8 VEHICLE_VTOL_STATE_FW = 4
uint64 timestamp # time since system start (microseconds)
bool vtol_in_rw_mode # true: vtol vehicle is in rotating wing mode
bool vtol_in_trans_mode
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
uint8 vehicle_vtol_state # current state of the vtol, see VEHICLE_VTOL_STATE
bool vtol_transition_failsafe # vtol in transition failsafe mode
bool fw_permanent_stab # In fw mode stabilize attitude even if in manual mode
+10
View File
@@ -55,6 +55,16 @@ endif()
# build NuttX
add_subdirectory(NuttX ${PX4_BINARY_DIR}/NuttX)
# check that CONFIG_ARCH_BOARD_CUSTOM_DIR is in PX4_BOARD_DIR
if(CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH)
get_filename_component(nuttx_defconfig_root "${NUTTX_DEFCONFIG}/../.." ABSOLUTE)
get_filename_component(nuttx_config_from_defconfig "${NUTTX_DIR}/${CONFIG_ARCH_BOARD_CUSTOM_DIR}" ABSOLUTE)
if(NOT ${nuttx_defconfig_root} MATCHES ${nuttx_config_from_defconfig})
message(FATAL_ERROR "NuttX custom board directory (${CONFIG_ARCH_BOARD_CUSTOM_DIR}) isn't in board directory (${PX4_BOARD_DIR})")
endif()
endif()
set(nuttx_libs)
set(SCRIPT_PREFIX)
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
@@ -34,13 +34,13 @@
/**
* @file EscClient.hpp
*
* Client-side implementation of DS-15 specification ESC service
* Client-side implementation of UDRAL specification ESC service
*
* Publishes the following UAVCAN v1 messages:
* Publishes the following Cyphal messages:
* reg.drone.service.actuator.common.sp.Value8.0.1
* reg.drone.service.common.Readiness.0.1
*
* Subscribes to the following UAVCAN v1 messages:
* Subscribes to the following Cyphal messages:
* reg.drone.service.actuator.common.Feedback.0.1
* reg.drone.service.actuator.common.Status.0.1
*
@@ -57,9 +57,9 @@
#include <drivers/drv_hrt.h>
#include <lib/mixer_module/mixer_module.hpp>
// DS-15 Specification Messages
#include <reg/drone/service/actuator/common/sp/Vector31_0_1.h>
#include <reg/drone/service/common/Readiness_0_1.h>
// UDRAL Specification Messages
#include <reg/udral/service/actuator/common/sp/Vector31_0_1.h>
#include <reg/udral/service/common/Readiness_0_1.h>
/// TODO: Allow derived class of Subscription at same time, to handle ESC Feedback/Status
class UavcanEscController : public UavcanPublisher
@@ -67,8 +67,8 @@ class UavcanEscController : public UavcanPublisher
public:
static constexpr int MAX_ACTUATORS = MixingOutput::MAX_ACTUATORS;
UavcanEscController(CanardInstance &ins, UavcanParamManager &pmgr) :
UavcanPublisher(ins, pmgr, "ds_015", "esc") { };
UavcanEscController(CanardHandle &handle, UavcanParamManager &pmgr) :
UavcanPublisher(handle, pmgr, "udral", "esc") { };
~UavcanEscController() {};
@@ -80,45 +80,47 @@ public:
if (new_arming.armed != _armed.armed) {
_armed = new_arming;
size_t payload_size = reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_;
// Only publish if we have a valid publication ID set
if (_port_id == 0) {
return;
}
reg_drone_service_common_Readiness_0_1 msg_arming {};
reg_udral_service_common_Readiness_0_1 msg_arming {};
if (_armed.armed) {
msg_arming.value = reg_drone_service_common_Readiness_0_1_ENGAGED;
msg_arming.value = reg_udral_service_common_Readiness_0_1_ENGAGED;
} else if (_armed.prearmed) {
msg_arming.value = reg_drone_service_common_Readiness_0_1_STANDBY;
msg_arming.value = reg_udral_service_common_Readiness_0_1_STANDBY;
} else {
msg_arming.value = reg_drone_service_common_Readiness_0_1_SLEEP;
msg_arming.value = reg_udral_service_common_Readiness_0_1_SLEEP;
}
uint8_t arming_payload_buffer[reg_drone_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
uint8_t arming_payload_buffer[reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
CanardPortID arming_pid = static_cast<CanardPortID>(static_cast<uint32_t>(_port_id) + 1);
CanardTransfer transfer = {
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
const CanardTransferMetadata transfer_metadata = {
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = arming_pid, // This is the subject-ID.
.remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
.transfer_id = _arming_transfer_id,
.payload_size = reg_drone_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_,
.payload = &arming_payload_buffer,
};
int result = reg_drone_service_common_Readiness_0_1_serialize_(&msg_arming, arming_payload_buffer,
&transfer.payload_size);
int result = reg_udral_service_common_Readiness_0_1_serialize_(&msg_arming, arming_payload_buffer,
&payload_size);
if (result == 0) {
// set the data ready in the buffer and chop if needed
++_arming_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
result = canardTxPush(&_canard_instance, &transfer);
result = _canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
&transfer_metadata,
payload_size,
&arming_payload_buffer
);
}
}
}
@@ -127,7 +129,8 @@ public:
void update_outputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs)
{
if (_port_id > 0) {
reg_drone_service_actuator_common_sp_Vector31_0_1 msg_sp {0};
reg_udral_service_actuator_common_sp_Vector31_0_1 msg_sp {0};
size_t payload_size = reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_;
for (uint8_t i = 0; i < MAX_ACTUATORS; i++) {
if (i < num_outputs) {
@@ -139,29 +142,30 @@ public:
}
}
PX4_INFO("Publish %d values %f, %f, %f, %f", num_outputs, (double)msg_sp.value[0], (double)msg_sp.value[1],
(double)msg_sp.value[2], (double)msg_sp.value[3]);
uint8_t esc_sp_payload_buffer[reg_drone_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
uint8_t esc_sp_payload_buffer[reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
CanardTransfer transfer = {
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
const CanardTransferMetadata transfer_metadata = {
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = _port_id, // This is the subject-ID.
.remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
.transfer_id = _transfer_id,
.payload_size = reg_drone_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_,
.payload = &esc_sp_payload_buffer,
};
int result = reg_drone_service_actuator_common_sp_Vector31_0_1_serialize_(&msg_sp, esc_sp_payload_buffer,
&transfer.payload_size);
int result = reg_udral_service_actuator_common_sp_Vector31_0_1_serialize_(&msg_sp, esc_sp_payload_buffer,
&payload_size);
if (result == 0) {
// set the data ready in the buffer and chop if needed
++_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
result = canardTxPush(&_canard_instance, &transfer);
result = _canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
&transfer_metadata,
payload_size,
&esc_sp_payload_buffer);
}
}
};
@@ -175,7 +179,7 @@ private:
/**
* ESC status message reception will be reported via this callback.
*/
void esc_status_sub_cb(const CanardTransfer &msg);
void esc_status_sub_cb(const CanardRxTransfer &msg);
uint8_t _rotor_count {0};
@@ -34,14 +34,14 @@
/**
* @file EscServer.hpp
*
* Server-side implementation of DS-15 specification ESC service
* Server-side implementation of UDRAL specification ESC service
* (Used for CANNode control of an ESC via PWM output)
*
* Subscribes to the following UAVCAN v1 messages:
* Subscribes to the following Cyphal messages:
* reg.drone.service.actuator.common.sp.Value8.0.1
* reg.drone.service.common.Readiness.0.1
*
* Publishes to the following UAVCAN v1 messages:
* Publishes to the following Cyphal messages:
* reg.drone.service.actuator.common.Feedback.0.1
* reg.drone.service.actuator.common.Status.0.1
*
@@ -62,7 +62,7 @@
#include <drivers/drv_hrt.h>
#include <lib/mixer_module/mixer_module.hpp>
// DS-15 Specification Messages
// UDRAL Specification Messages
#include <reg/drone/service/actuator/common/sp/Vector31_0_1.h>
#include <reg/drone/service/common/Readiness_0_1.h>
@@ -41,7 +41,7 @@ px4_add_git_submodule(TARGET git_legacy_data_types PATH ${LEGACY_DSDL_DIR})
find_program(NNVG_PATH nnvg)
if(NNVG_PATH)
message("Generating UAVCANv1 DSDL headers using Nunavut")
message("Generating Cyphal DSDL headers using Nunavut")
execute_process(COMMAND ${NNVG_PATH} --outdir ${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated --target-language c -I ${DSDL_DIR}/uavcan ${DSDL_DIR}/reg)
execute_process(COMMAND ${NNVG_PATH} --outdir ${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated --target-language c -I ${LEGACY_DSDL_DIR}/uavcan ${LEGACY_DSDL_DIR}/legacy)
execute_process(COMMAND ${NNVG_PATH} --outdir ${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated --target-language c ${DSDL_DIR}/uavcan)
@@ -66,14 +66,14 @@ if(${PX4_PLATFORM} MATCHES "nuttx")
endif()
endif()
if(CONFIG_UAVCAN_V1_NODE_MANAGER)
if(CONFIG_CYPHAL_NODE_MANAGER)
list(APPEND SRCS
NodeManager.hpp
NodeManager.cpp
)
endif()
if(CONFIG_UAVCAN_V1_NODE_CLIENT)
if(CONFIG_CYPHAL_NODE_CLIENT)
list(APPEND SRCS
NodeClient.hpp
NodeClient.cpp
@@ -86,29 +86,31 @@ endif()
# Temporary measure to get Kconfig option as defines into this application
# Ideally we want nicely decouple and define this in kconfig.cmake
# But then we need to overhaul the src modules naming convention
set(DRIVERS_UAVCAN_V1_OPTIONS)
set(DRIVERS_CYPHAL_OPTIONS)
get_cmake_property(_variableNames VARIABLES)
foreach (_variableName ${_variableNames})
string(REGEX MATCH "^CONFIG_UAVCAN_V1_" UAVCAN_V1_OPTION ${_variableName})
string(REGEX MATCH "^CONFIG_CYPHAL_" CYPHAL_OPTION ${_variableName})
if(UAVCAN_V1_OPTION)
if(CYPHAL_OPTION)
if(${${_variableName}} STREQUAL "y")
list(APPEND DRIVERS_UAVCAN_V1_OPTIONS "-D${_variableName}=1")
list(APPEND DRIVERS_CYPHAL_OPTIONS "-D${_variableName}=1")
else()
list(APPEND DRIVERS_UAVCAN_V1_OPTIONS "-D${_variableName}=${${_variableName}}")
list(APPEND DRIVERS_CYPHAL_OPTIONS "-D${_variableName}=${${_variableName}}")
endif()
endif()
endforeach()
remove_definitions(-Werror)
px4_add_module(
MODULE drivers__uavcan_v1
MAIN uavcan_v1
MODULE drivers__cyphal
MAIN cyphal
STACK_MAIN 4096
COMPILE_FLAGS
#-DCANARD_ASSERT
-DUINT32_C\(x\)=__UINT32_C\(x\)
-O0
${DRIVERS_UAVCAN_V1_OPTIONS}
${DRIVERS_CYPHAL_OPTIONS}
INCLUDES
${LIBCANARD_DIR}/libcanard/
${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated
@@ -119,8 +121,9 @@ px4_add_module(
SubscriptionManager.hpp
ParamManager.hpp
ParamManager.cpp
Uavcan.cpp
Uavcan.hpp
Cyphal.cpp
Cyphal.hpp
CanardHandle.cpp
Publishers/uORB/uorb_publisher.cpp
Subscribers/uORB/uorb_subscriber.cpp
${SRCS}
@@ -137,3 +140,6 @@ px4_add_module(
version
${DPNDS}
)
# libcanard 3.0 introduces this warning, for now no intention to fix it thus we ignore this warning
set_source_files_properties(${LIBCANARD_DIR}/libcanard/canard.c PROPERTIES COMPILE_FLAGS -Wno-cast-align)
+221
View File
@@ -0,0 +1,221 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "CanardHandle.hpp"
#include <net/if.h>
#include <sys/ioctl.h>
#include <string.h>
#include <px4_platform_common/log.h>
#include "o1heap/o1heap.h"
#include "Subscribers/BaseSubscriber.hpp"
#if defined(__PX4_NUTTX)
# if defined(CONFIG_NET_CAN)
# include "CanardSocketCAN.hpp"
# elif defined(CONFIG_CAN)
# include "CanardNuttXCDev.hpp"
# endif // CONFIG_CAN
#endif // NuttX
O1HeapInstance *cyphal_allocator{nullptr};
static void *memAllocate(CanardInstance *const ins, const size_t amount) { return o1heapAllocate(cyphal_allocator, amount); }
static void memFree(CanardInstance *const ins, void *const pointer) { o1heapFree(cyphal_allocator, pointer); }
CanardHandle::CanardHandle(uint32_t node_id, const size_t capacity, const size_t mtu_bytes)
{
_cyphal_heap = memalign(O1HEAP_ALIGNMENT, HeapSize);
cyphal_allocator = o1heapInit(_cyphal_heap, HeapSize, nullptr, nullptr);
if (cyphal_allocator == nullptr) {
PX4_ERR("o1heapInit failed with size %u", HeapSize);
}
_canard_instance = canardInit(&memAllocate, &memFree);
_canard_instance.node_id = node_id; // Defaults to anonymous; can be set up later at any point.
_queue = canardTxInit(capacity, mtu_bytes);
#if defined(__PX4_NUTTX)
# if defined(CONFIG_NET_CAN)
_can_interface = new CanardSocketCAN();
# elif defined(CONFIG_CAN)
_can_interface = new CanardNuttXCDev();
# endif // CONFIG_CAN
#endif // NuttX
}
CanardHandle::~CanardHandle()
{
_can_interface->close();
delete _can_interface;
_can_interface = nullptr;
delete static_cast<uint8_t *>(_cyphal_heap);
_cyphal_heap = nullptr;
}
bool CanardHandle::init()
{
if (_can_interface) {
if (_can_interface->init() == PX4_OK) {
return true;
}
}
return false;
}
void CanardHandle::receive()
{
/* Process received messages */
uint8_t data[64] {};
CanardRxFrame received_frame{};
received_frame.frame.payload = &data;
while (_can_interface->receive(&received_frame) > 0) {
CanardRxTransfer receive{};
CanardRxSubscription *subscription = nullptr;
int32_t result = canardRxAccept(&_canard_instance, received_frame.timestamp_usec, &received_frame.frame, 0, &receive,
&subscription);
if (result < 0) {
// An error has occurred: either an argument is invalid or we've ran out of memory.
// It is possible to statically prove that an out-of-memory will never occur for a given application if
// the heap is sized correctly; for background, refer to the Robson's Proof and the documentation for O1Heap.
// Reception of an invalid frame is NOT an error.
PX4_ERR("Receive error %" PRId32" \n", result);
} else if (result == 1) {
// A transfer has been received, process it.
// PX4_INFO("received Port ID: %d", receive.port_id);
if (subscription != nullptr) {
UavcanBaseSubscriber *sub_instance = (UavcanBaseSubscriber *)subscription->user_reference;
sub_instance->callback(receive);
} else {
PX4_ERR("No matching sub for %d", receive.metadata.port_id);
}
// Deallocate the dynamic memory afterwards.
_canard_instance.memory_free(&_canard_instance, (void *)receive.payload);
} else {
//PX4_INFO("RX canard %d", result);
}
}
}
void CanardHandle::transmit()
{
// Look at the top of the TX queue.
for (const CanardTxQueueItem *ti = NULL; (ti = canardTxPeek(&_queue)) != NULL;) { // Peek at the top of the queue.
if ((0U == ti->tx_deadline_usec) || (ti->tx_deadline_usec > hrt_absolute_time())) { // Check the deadline.
// Send the frame. Redundant interfaces may be used here.
const int tx_res = _can_interface->transmit(*ti);
if (tx_res < 0) {
PX4_ERR("Transmit error %d, frame dropped, errno '%s'", tx_res, strerror(errno));
} else if (tx_res == 0) {
// Timeout - just exit and try again later
break;
}
}
// After the frame is transmitted or if it has timed out while waiting, pop it from the queue and deallocate:
_canard_instance.memory_free(&_canard_instance, canardTxPop(&_queue, ti));
}
}
int32_t CanardHandle::TxPush(const CanardMicrosecond tx_deadline_usec,
const CanardTransferMetadata *const metadata,
const size_t payload_size,
const void *const payload)
{
return canardTxPush(&_queue, &_canard_instance, tx_deadline_usec, metadata, payload_size, payload);
}
int8_t CanardHandle::RxSubscribe(const CanardTransferKind transfer_kind,
const CanardPortID port_id,
const size_t extent,
const CanardMicrosecond transfer_id_timeout_usec,
CanardRxSubscription *const out_subscription)
{
return canardRxSubscribe(&_canard_instance, transfer_kind, port_id, extent, transfer_id_timeout_usec, out_subscription);
}
int8_t CanardHandle::RxUnsubscribe(const CanardTransferKind transfer_kind,
const CanardPortID port_id)
{
return canardRxUnsubscribe(&_canard_instance, transfer_kind, port_id);
}
CanardTreeNode *CanardHandle::getRxSubscriptions(CanardTransferKind kind)
{
return _canard_instance.rx_subscriptions[kind];
}
O1HeapDiagnostics CanardHandle::getO1HeapDiagnostics()
{
return o1heapGetDiagnostics(cyphal_allocator);
}
int32_t CanardHandle::mtu()
{
return _queue.mtu_bytes;
}
CanardNodeID CanardHandle::node_id()
{
return _canard_instance.node_id;
}
void CanardHandle::set_node_id(CanardNodeID id)
{
_canard_instance.node_id = id;
}
+87
View File
@@ -0,0 +1,87 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#pragma once
#include <canard.h>
#include "o1heap/o1heap.h"
#include "CanardInterface.hpp"
class CanardHandle
{
/*
* This memory is allocated for the 01Heap allocator used by
* libcanard to store incoming/outcoming data
* Current size of 8192 bytes is arbitrary, should be optimized further
* when more nodes and messages are on the CAN bus
*/
static constexpr unsigned HeapSize = 8192;
public:
CanardHandle(uint32_t node_id, const size_t capacity, const size_t mtu_bytes);
~CanardHandle();
bool init();
void receive();
void transmit();
int32_t TxPush(const CanardMicrosecond tx_deadline_usec,
const CanardTransferMetadata *const metadata,
const size_t payload_size,
const void *const payload);
int8_t RxSubscribe(const CanardTransferKind transfer_kind,
const CanardPortID port_id,
const size_t extent,
const CanardMicrosecond transfer_id_timeout_usec,
CanardRxSubscription *const out_subscription);
int8_t RxUnsubscribe(const CanardTransferKind transfer_kind,
const CanardPortID port_id);
CanardTreeNode *getRxSubscriptions(CanardTransferKind kind);
O1HeapDiagnostics getO1HeapDiagnostics();
int32_t mtu();
CanardNodeID node_id();
void set_node_id(CanardNodeID id);
private:
CanardInterface *_can_interface;
CanardInstance _canard_instance;
CanardTxQueue _queue;
void *_cyphal_heap{nullptr};
};
@@ -35,6 +35,14 @@
#include <canard.h>
/// One frame stored in the transmission queue along with its metadata.
struct CanardRxFrame {
CanardMicrosecond timestamp_usec;
/// The actual CAN frame data.
CanardFrame frame;
};
class CanardInterface
{
public:
@@ -48,12 +56,12 @@ public:
/// Send a CanardFrame
/// This function is blocking
/// The return value is number of bytes transferred, negative value on error.
virtual int16_t transmit(const CanardFrame &txframe, int timeout_ms = 0) = 0;
virtual int16_t transmit(const CanardTxQueueItem &txframe, int timeout_ms = 0) = 0;
/// Receive a CanardFrame
/// This function is blocking
/// The return value is number of bytes received, negative value on error.
virtual int16_t receive(CanardFrame *rxf) = 0;
virtual int16_t receive(CanardRxFrame *rxf) = 0;
private:
@@ -65,7 +65,7 @@ int CanardNuttXCDev::init()
return 0;
}
int16_t CanardNuttXCDev::transmit(const CanardFrame &txf, int timeout_ms)
int16_t CanardNuttXCDev::transmit(const CanardTxQueueItem &txf, int timeout_ms)
{
if (_fd < 0) {
return -1;
@@ -93,13 +93,13 @@ int16_t CanardNuttXCDev::transmit(const CanardFrame &txf, int timeout_ms)
struct can_msg_s transmit_msg {};
transmit_msg.cm_hdr.ch_id = txf.extended_can_id;
transmit_msg.cm_hdr.ch_id = txf.frame.extended_can_id;
transmit_msg.cm_hdr.ch_dlc = txf.payload_size;
transmit_msg.cm_hdr.ch_dlc = txf.frame.payload_size;
transmit_msg.cm_hdr.ch_extid = 1;
memcpy(transmit_msg.cm_data, txf.payload, txf.payload_size);
memcpy(transmit_msg.cm_data, txf.frame.payload, txf.frame.payload_size);
const size_t msg_len = CAN_MSGLEN(transmit_msg.cm_hdr.ch_dlc);
@@ -112,7 +112,7 @@ int16_t CanardNuttXCDev::transmit(const CanardFrame &txf, int timeout_ms)
return 1;
}
int16_t CanardNuttXCDev::receive(CanardFrame *received_frame)
int16_t CanardNuttXCDev::receive(CanardRxFrame *received_frame)
{
if ((_fd < 0) || (received_frame == nullptr)) {
return -1;
@@ -140,9 +140,9 @@ int16_t CanardNuttXCDev::receive(CanardFrame *received_frame)
return -1;
} else {
received_frame->extended_can_id = receive_msg.cm_hdr.ch_id;
received_frame->payload_size = receive_msg.cm_hdr.ch_dlc;
memcpy((void *)received_frame->payload, receive_msg.cm_data, receive_msg.cm_hdr.ch_dlc);
received_frame->frame.extended_can_id = receive_msg.cm_hdr.ch_id;
received_frame->frame.payload_size = receive_msg.cm_hdr.ch_dlc;
memcpy((void *)received_frame->frame.payload, receive_msg.cm_data, receive_msg.cm_hdr.ch_dlc);
return nbytes;
}
}
@@ -51,15 +51,15 @@ public:
/// The return value is 0 on succes and -1 on error
int init();
/// Send a CanardFrame to the CanardSocketInstance socket
/// Send a CanardTxQueueItem to the CanardSocketInstance socket
/// This function is blocking
/// The return value is number of bytes transferred, negative value on error.
int16_t transmit(const CanardFrame &txframe, int timeout_ms = 0);
int16_t transmit(const CanardTxQueueItem &txframe, int timeout_ms = 0);
/// Receive a CanardFrame from the CanardSocketInstance socket
/// Receive a CanardRxFrame from the CanardSocketInstance socket
/// This function is blocking
/// The return value is number of bytes received, negative value on error.
int16_t receive(CanardFrame *rxf);
int16_t receive(CanardRxFrame *rxf);
private:
int _fd{-1};
@@ -152,22 +152,22 @@ int CanardSocketCAN::init()
return 0;
}
int16_t CanardSocketCAN::transmit(const CanardFrame &txf, int timeout_ms)
int16_t CanardSocketCAN::transmit(const CanardTxQueueItem &txf, int timeout_ms)
{
/* Copy CanardFrame to can_frame/canfd_frame */
if (_can_fd) {
_send_frame.can_id = txf.extended_can_id | CAN_EFF_FLAG;
_send_frame.len = txf.payload_size;
memcpy(&_send_frame.data, txf.payload, txf.payload_size);
_send_frame.can_id = txf.frame.extended_can_id | CAN_EFF_FLAG;
_send_frame.len = txf.frame.payload_size;
memcpy(&_send_frame.data, txf.frame.payload, txf.frame.payload_size);
} else {
struct can_frame *frame = (struct can_frame *)&_send_frame;
frame->can_id = txf.extended_can_id | CAN_EFF_FLAG;
frame->can_dlc = txf.payload_size;
memcpy(&frame->data, txf.payload, txf.payload_size);
frame->can_id = txf.frame.extended_can_id | CAN_EFF_FLAG;
frame->can_dlc = txf.frame.payload_size;
memcpy(&frame->data, txf.frame.payload, txf.frame.payload_size);
}
uint64_t deadline_systick = getMonotonicTimestampUSec() + (txf.timestamp_usec - hrt_absolute_time()) +
uint64_t deadline_systick = getMonotonicTimestampUSec() + (txf.tx_deadline_usec - hrt_absolute_time()) +
CONFIG_USEC_PER_TICK; // Compensate for precision loss when converting hrt to systick
/* Set CAN_RAW_TX_DEADLINE timestamp */
@@ -177,7 +177,7 @@ int16_t CanardSocketCAN::transmit(const CanardFrame &txf, int timeout_ms)
return sendmsg(_fd, &_send_msg, 0);
}
int16_t CanardSocketCAN::receive(CanardFrame *rxf)
int16_t CanardSocketCAN::receive(CanardRxFrame *rxf)
{
int32_t result = recvmsg(_fd, &_recv_msg, MSG_DONTWAIT);
@@ -189,15 +189,15 @@ int16_t CanardSocketCAN::receive(CanardFrame *rxf)
if (_can_fd) {
struct canfd_frame *recv_frame = (struct canfd_frame *)&_recv_frame;
rxf->extended_can_id = recv_frame->can_id & CAN_EFF_MASK;
rxf->payload_size = recv_frame->len;
rxf->payload = &recv_frame->data;
rxf->frame.extended_can_id = recv_frame->can_id & CAN_EFF_MASK;
rxf->frame.payload_size = recv_frame->len;
rxf->frame.payload = &recv_frame->data;
} else {
struct can_frame *recv_frame = (struct can_frame *)&_recv_frame;
rxf->extended_can_id = recv_frame->can_id & CAN_EFF_MASK;
rxf->payload_size = recv_frame->can_dlc;
rxf->payload = &recv_frame->data; //FIXME either copy or clearly state the pointer reference
rxf->frame.extended_can_id = recv_frame->can_id & CAN_EFF_MASK;
rxf->frame.payload_size = recv_frame->can_dlc;
rxf->frame.payload = &recv_frame->data; //FIXME either copy or clearly state the pointer reference
}
/* Read SO_TIMESTAMP value */
@@ -71,12 +71,12 @@ public:
/// Send a CanardFrame to the CanardSocketInstance socket
/// This function is blocking
/// The return value is number of bytes transferred, negative value on error.
int16_t transmit(const CanardFrame &txframe, int timeout_ms = 0);
int16_t transmit(const CanardTxQueueItem &txframe, int timeout_ms = 0);
/// Receive a CanardFrame from the CanardSocketInstance socket
/// This function is blocking
/// The return value is number of bytes received, negative value on error.
int16_t receive(CanardFrame *rxf);
int16_t receive(CanardRxFrame *rxf);
// TODO implement ioctl for CAN filter
//int16_t socketcanConfigureFilter(const fd_t fd, const size_t num_filters, const struct can_filter *filters);
@@ -31,13 +31,13 @@
*
****************************************************************************/
#include "Uavcan.hpp"
#include "Cyphal.hpp"
#include <lib/geo/geo.h>
#include <lib/version/version.h>
#ifdef CONFIG_UAVCAN_V1_APP_DESCRIPTOR
#ifdef CONFIG_CYPHAL_APP_DESCRIPTOR
#include "boot_app_shared.h"
/*
* This is the AppImageDescriptor used
@@ -60,54 +60,22 @@ boot_app_shared_section app_descriptor_t AppDescriptor = {
using namespace time_literals;
UavcanNode *UavcanNode::_instance;
CyphalNode *CyphalNode::_instance;
O1HeapInstance *uavcan_allocator{nullptr};
static void *memAllocate(CanardInstance *const ins, const size_t amount) { return o1heapAllocate(uavcan_allocator, amount); }
static void memFree(CanardInstance *const ins, void *const pointer) { o1heapFree(uavcan_allocator, pointer); }
#if defined(__PX4_NUTTX)
# if defined(CONFIG_NET_CAN)
# include "CanardSocketCAN.hpp"
# elif defined(CONFIG_CAN)
# include "CanardNuttXCDev.hpp"
# endif // CONFIG_CAN
#endif // NuttX
UavcanNode::UavcanNode(CanardInterface *interface, uint32_t node_id) :
CyphalNode::CyphalNode(uint32_t node_id, size_t capacity, size_t mtu_bytes) :
ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::uavcan),
_can_interface(interface)
_canard_handle(node_id, capacity, mtu_bytes)
{
pthread_mutex_init(&_node_mutex, nullptr);
_uavcan_heap = memalign(O1HEAP_ALIGNMENT, HeapSize);
uavcan_allocator = o1heapInit(_uavcan_heap, HeapSize, nullptr, nullptr);
if (uavcan_allocator == nullptr) {
PX4_ERR("o1heapInit failed with size %u", HeapSize);
}
_canard_instance = canardInit(&memAllocate, &memFree);
_canard_instance.node_id = node_id; // Defaults to anonymous; can be set up later at any point.
bool can_fd = false;
if (can_fd) {
_canard_instance.mtu_bytes = CANARD_MTU_CAN_FD;
} else {
_canard_instance.mtu_bytes = CANARD_MTU_CAN_CLASSIC;
}
#ifdef CONFIG_UAVCAN_V1_NODE_MANAGER
#ifdef CONFIG_CYPHAL_NODE_MANAGER
_node_manager.subscribe();
#endif
#ifdef CONFIG_UAVCAN_V1_NODE_CLIENT
_node_client = new NodeClient(_canard_instance, _param_manager);
#ifdef CONFIG_CYPHAL_NODE_CLIENT
_node_client = new NodeClient(_canard_handle, _param_manager);
_node_client->subscribe();
#endif
@@ -117,7 +85,7 @@ UavcanNode::UavcanNode(CanardInterface *interface, uint32_t node_id) :
_sub_manager.subscribe();
}
UavcanNode::~UavcanNode()
CyphalNode::~CyphalNode()
{
if (_instance) {
/* tell the task we want it to go away */
@@ -138,32 +106,25 @@ UavcanNode::~UavcanNode()
} while (_instance);
}
delete _can_interface;
_can_interface = nullptr;
perf_free(_cycle_perf);
perf_free(_interval_perf);
delete static_cast<uint8_t *>(_uavcan_heap);
_uavcan_heap = nullptr;
}
int UavcanNode::start(uint32_t node_id, uint32_t bitrate)
int CyphalNode::start(uint32_t node_id, uint32_t bitrate)
{
if (_instance != nullptr) {
PX4_WARN("Already started");
return -1;
}
#if defined(__PX4_NUTTX)
# if defined(CONFIG_NET_CAN)
CanardInterface *interface = new CanardSocketCAN();
# elif defined(CONFIG_CAN)
CanardInterface *interface = new CanardNuttXCDev();
# endif // CONFIG_CAN
#endif // NuttX
bool can_fd = false;
_instance = new UavcanNode(interface, node_id);
if (can_fd) {
_instance = new CyphalNode(node_id, 8, CANARD_MTU_CAN_FD);
} else {
_instance = new CyphalNode(node_id, 64, CANARD_MTU_CAN_CLASSIC);
}
if (_instance == nullptr) {
PX4_ERR("Out of memory");
@@ -178,17 +139,16 @@ int UavcanNode::start(uint32_t node_id, uint32_t bitrate)
return PX4_OK;
}
void UavcanNode::init()
void CyphalNode::init()
{
// interface init
if (_can_interface) {
if (_can_interface->init() == PX4_OK) {
_initialized = true;
}
if (_canard_handle.init()) {
_initialized = true;
}
}
void UavcanNode::Run()
void CyphalNode::Run()
{
pthread_mutex_lock(&_node_mutex);
@@ -221,22 +181,22 @@ void UavcanNode::Run()
perf_begin(_cycle_perf);
perf_count(_interval_perf);
if (_canard_instance.node_id != CANARD_NODE_ID_UNSET) {
if (_canard_handle.node_id() != CANARD_NODE_ID_UNSET) {
// send uavcan::node::Heartbeat_1_0 @ 1 Hz
sendHeartbeat();
// Check all publishers
_pub_manager.update();
#ifdef CONFIG_UAVCAN_V1_NODE_MANAGER
#ifdef CONFIG_CYPHAL_NODE_MANAGER
_node_manager.update();
#endif
}
#ifdef CONFIG_UAVCAN_V1_NODE_CLIENT
#ifdef CONFIG_CYPHAL_NODE_CLIENT
else if (_node_client != nullptr) {
if (_canard_instance.node_id == CANARD_NODE_ID_UNSET) {
if (_canard_handle.node_id() == CANARD_NODE_ID_UNSET) {
_node_client->update();
} else {
@@ -246,56 +206,19 @@ void UavcanNode::Run()
#endif
transmit();
_canard_handle.transmit();
/* Process received messages */
_canard_handle.receive();
uint8_t data[64] {};
CanardFrame received_frame{};
received_frame.payload = &data;
while (!_task_should_exit.load() && _can_interface->receive(&received_frame) > 0) {
CanardTransfer receive{};
CanardRxSubscription *subscription = nullptr;
int32_t result = canardRxAccept2(&_canard_instance, &received_frame, 0, &receive, &subscription);
if (result < 0) {
// An error has occurred: either an argument is invalid or we've ran out of memory.
// It is possible to statically prove that an out-of-memory will never occur for a given application if
// the heap is sized correctly; for background, refer to the Robson's Proof and the documentation for O1Heap.
// Reception of an invalid frame is NOT an error.
PX4_ERR("Receive error %" PRId32" \n", result);
} else if (result == 1) {
// A transfer has been received, process it.
// PX4_INFO("received Port ID: %d", receive.port_id);
if (subscription != nullptr) {
UavcanBaseSubscriber *sub_instance = (UavcanBaseSubscriber *)subscription->user_reference;
sub_instance->callback(receive);
} else {
PX4_ERR("No matching sub for %d", receive.port_id);
}
// Deallocate the dynamic memory afterwards.
_canard_instance.memory_free(&_canard_instance, (void *)receive.payload);
} else {
//PX4_INFO("RX canard %d", result);
}
}
// Pop canardTx queue to send out responses to requets
transmit();
// Pop canardTx queue to send out responses to requests
_canard_handle.transmit();
perf_end(_cycle_perf);
if (_instance && _task_should_exit.load()) {
ScheduleClear();
if (_initialized && _can_interface != nullptr) {
_can_interface->close();
if (_initialized) {
_initialized = false;
}
@@ -305,55 +228,24 @@ void UavcanNode::Run()
pthread_mutex_unlock(&_node_mutex);
}
void UavcanNode::transmit()
template <typename As, typename F>
static void traverseTree(const CanardTreeNode *const root, const F &op) // NOLINT this recursion is tightly bounded
{
// Look at the top of the TX queue.
for (const CanardFrame *txf = nullptr; (txf = canardTxPeek(&_canard_instance)) != nullptr;) {
// Attempt transmission only if the frame is not yet timed out while waiting in the TX queue.
// Otherwise just drop it and move on to the next one.
const hrt_abstime now = hrt_absolute_time();
if (txf->timestamp_usec == 0 || txf->timestamp_usec > now) {
// Send the frame. Redundant interfaces may be used here.
const int tx_res = _can_interface->transmit(*txf);
if (tx_res < 0) {
// Failure - drop the frame and report
canardTxPop(&_canard_instance);
// Deallocate the dynamic memory afterwards.
_canard_instance.memory_free(&_canard_instance, (CanardFrame *)txf);
PX4_ERR("Transmit error %d, frame dropped, errno '%s'", tx_res, strerror(errno));
} else if (tx_res > 0) {
// Success - just drop the frame
canardTxPop(&_canard_instance);
// Deallocate the dynamic memory afterwards.
_canard_instance.memory_free(&_canard_instance, (CanardFrame *)txf);
} else {
// Timeout - just exit and try again later
break;
}
} else if (txf->timestamp_usec <= now) {
// Transmission timed out -- remove from queue and deallocate its memory
canardTxPop(&_canard_instance);
_canard_instance.memory_free(&_canard_instance, (CanardFrame *)txf);
}
if (root != nullptr) {
traverseTree<As, F>(root->lr[0], op);
op(static_cast<const As *>(static_cast<const void *>(root)));
traverseTree<As, F>(root->lr[1], op);
}
}
void UavcanNode::print_info()
void CyphalNode::print_info()
{
pthread_mutex_lock(&_node_mutex);
perf_print_counter(_cycle_perf);
perf_print_counter(_interval_perf);
O1HeapDiagnostics heap_diagnostics = o1heapGetDiagnostics(uavcan_allocator);
O1HeapDiagnostics heap_diagnostics = _canard_handle.getO1HeapDiagnostics();
PX4_INFO("Heap status %zu/%zu Peak alloc %zu Peak req %zu OOM count %" PRIu64,
heap_diagnostics.allocated, heap_diagnostics.capacity,
@@ -362,44 +254,36 @@ void UavcanNode::print_info()
_pub_manager.printInfo();
CanardRxSubscription *rxs = _canard_instance.rx_subscriptions[CanardTransferKindMessage];
while (rxs != nullptr) {
if (rxs->user_reference == nullptr) {
PX4_INFO("Message port id %d", rxs->port_id);
traverseTree<CanardRxSubscription>(_canard_handle.getRxSubscriptions(CanardTransferKindMessage),
[&](const CanardRxSubscription * const sub) {
if (sub->user_reference == nullptr) {
PX4_INFO("Message port id %d", sub->port_id);
} else {
((UavcanBaseSubscriber *)rxs->user_reference)->printInfo();
((UavcanBaseSubscriber *)sub->user_reference)->printInfo();
}
});
rxs = rxs->next;
}
rxs = _canard_instance.rx_subscriptions[CanardTransferKindRequest];
while (rxs != nullptr) {
if (rxs->user_reference == nullptr) {
PX4_INFO("Service response port id %d", rxs->port_id);
traverseTree<CanardRxSubscription>(_canard_handle.getRxSubscriptions(CanardTransferKindRequest),
[&](const CanardRxSubscription * const sub) {
if (sub->user_reference == nullptr) {
PX4_INFO("Service response port id %d", sub->port_id);
} else {
((UavcanBaseSubscriber *)rxs->user_reference)->printInfo();
((UavcanBaseSubscriber *)sub->user_reference)->printInfo();
}
});
rxs = rxs->next;
}
rxs = _canard_instance.rx_subscriptions[CanardTransferKindResponse];
while (rxs != nullptr) {
if (rxs->user_reference == nullptr) {
PX4_INFO("Service request port id %d", rxs->port_id);
traverseTree<CanardRxSubscription>(_canard_handle.getRxSubscriptions(CanardTransferKindResponse),
[&](const CanardRxSubscription * const sub) {
if (sub->user_reference == nullptr) {
PX4_INFO("Service request port id %d", sub->port_id);
} else {
((UavcanBaseSubscriber *)rxs->user_reference)->printInfo();
((UavcanBaseSubscriber *)sub->user_reference)->printInfo();
}
rxs = rxs->next;
}
});
_mixing_output.printInfo();
@@ -412,7 +296,7 @@ static void print_usage()
"\tuavcannode {start|status|stop}");
}
extern "C" __EXPORT int uavcan_v1_main(int argc, char *argv[])
extern "C" __EXPORT int cyphal_main(int argc, char *argv[])
{
if (argc < 2) {
print_usage();
@@ -420,18 +304,18 @@ extern "C" __EXPORT int uavcan_v1_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "start")) {
if (UavcanNode::instance()) {
if (CyphalNode::instance()) {
PX4_ERR("already started");
return 1;
}
// CAN bitrate
int32_t bitrate = 0;
param_get(param_find("UAVCAN_V1_BAUD"), &bitrate);
param_get(param_find("CYPHAL_BAUD"), &bitrate);
// Node ID
int32_t node_id = 0;
param_get(param_find("UAVCAN_V1_ID"), &node_id);
param_get(param_find("CYPHAL_ID"), &node_id);
if (node_id == -1) {
node_id = CANARD_NODE_ID_UNSET;
@@ -439,11 +323,11 @@ extern "C" __EXPORT int uavcan_v1_main(int argc, char *argv[])
// Start
PX4_INFO("Node ID %" PRIu32 ", bitrate %" PRIu32, node_id, bitrate);
return UavcanNode::start(node_id, bitrate);
return CyphalNode::start(node_id, bitrate);
}
/* commands below require the app to be started */
UavcanNode *const inst = UavcanNode::instance();
CyphalNode *const inst = CyphalNode::instance();
if (!inst) {
PX4_ERR("application not running");
@@ -464,7 +348,7 @@ extern "C" __EXPORT int uavcan_v1_main(int argc, char *argv[])
return 1;
}
void UavcanNode::sendHeartbeat()
void CyphalNode::sendHeartbeat()
{
if (hrt_elapsed_time(&_uavcan_node_heartbeat_last) >= 1_s) {
@@ -473,21 +357,23 @@ void UavcanNode::sendHeartbeat()
heartbeat.health.value = uavcan_node_Health_1_0_NOMINAL;
heartbeat.mode.value = uavcan_node_Mode_1_0_OPERATIONAL;
const hrt_abstime now = hrt_absolute_time();
size_t payload_size = uavcan_node_Heartbeat_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_;
CanardTransfer transfer = {
.timestamp_usec = now + PUBLISHER_DEFAULT_TIMEOUT_USEC,
const CanardTransferMetadata transfer_metadata = {
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = uavcan_node_Heartbeat_1_0_FIXED_PORT_ID_,
.remote_node_id = CANARD_NODE_ID_UNSET,
.transfer_id = _uavcan_node_heartbeat_transfer_id++,
.payload_size = uavcan_node_Heartbeat_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_,
.payload = &_uavcan_node_heartbeat_buffer,
.transfer_id = _uavcan_node_heartbeat_transfer_id++
};
uavcan_node_Heartbeat_1_0_serialize_(&heartbeat, _uavcan_node_heartbeat_buffer, &transfer.payload_size);
uavcan_node_Heartbeat_1_0_serialize_(&heartbeat, _uavcan_node_heartbeat_buffer, &payload_size);
int32_t result = canardTxPush(&_canard_instance, &transfer);
int32_t result = _canard_handle.TxPush(now + PUBLISHER_DEFAULT_TIMEOUT_USEC,
&transfer_metadata,
payload_size,
&_uavcan_node_heartbeat_buffer
);
if (result < 0) {
// An error has occurred: either an argument is invalid or we've ran out of memory.
@@ -51,21 +51,18 @@
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/sensor_gps.h>
#include "o1heap/o1heap.h"
#include <canard.h>
#include <canard_dsdl.h>
#include "CanardInterface.hpp"
#include "Publishers/Publisher.hpp"
#include "Publishers/uORB/uorb_publisher.hpp"
#ifdef CONFIG_UAVCAN_V1_NODE_MANAGER
#ifdef CONFIG_CYPHAL_NODE_MANAGER
#include "NodeManager.hpp"
#endif
#ifdef CONFIG_UAVCAN_V1_NODE_CLIENT
#ifdef CONFIG_CYPHAL_NODE_CLIENT
#include "NodeClient.hpp"
#endif
@@ -76,8 +73,8 @@
/**
* UAVCAN mixing class.
* It is separate from UavcanNode to have 2 WorkItems and therefore allowing independent scheduling
* (I.e. UavcanMixingInterface runs upon actuator_control updates, whereas UavcanNode runs at
* It is separate from CyphalNode to have 2 WorkItems and therefore allowing independent scheduling
* (I.e. UavcanMixingInterface runs upon actuator_control updates, whereas CyphalNode runs at
* a fixed rate or upon bus updates).
* Both work items are expected to run on the same work queue.
*/
@@ -106,22 +103,15 @@ public:
protected:
void Run() override;
private:
friend class UavcanNode;
friend class CyphalNode;
pthread_mutex_t &_node_mutex;
UavcanEscController &_esc_controller;
// UavcanServoController &_servo_controller;
MixingOutput _mixing_output{"UCAN1_ESC", MAX_ACTUATORS, *this, MixingOutput::SchedulingPolicy::Auto, false, false};
};
class UavcanNode : public ModuleParams, public px4::ScheduledWorkItem
class CyphalNode : public ModuleParams, public px4::ScheduledWorkItem
{
/*
* This memory is allocated for the 01Heap allocator used by
* libcanard to store incoming/outcoming data
* Current size of 8192 bytes is arbitrary, should be optimized further
* when more nodes and messages are on the CAN bus
*/
static constexpr unsigned HeapSize = 8192;
/*
* Base interval, has to be complemented with events from the CAN driver
@@ -131,14 +121,14 @@ class UavcanNode : public ModuleParams, public px4::ScheduledWorkItem
public:
UavcanNode(CanardInterface *interface, uint32_t node_id);
~UavcanNode() override;
CyphalNode(uint32_t node_id, size_t capacity, size_t mtu_bytes);
~CyphalNode() override;
static int start(uint32_t node_id, uint32_t bitrate);
void print_info();
static UavcanNode *instance() { return _instance; }
static CyphalNode *instance() { return _instance; }
/* The bit rate that can be passed back to the bootloader */
int32_t active_bitrate{0};
@@ -148,22 +138,16 @@ private:
void Run() override;
void fill_node_info();
void transmit();
// Sends a heartbeat at 1s intervals
void sendHeartbeat();
void *_uavcan_heap{nullptr};
CanardInterface *_can_interface;
CanardInstance _canard_instance;
px4::atomic_bool _task_should_exit{false}; ///< flag to indicate to tear down the CAN driver
bool _initialized{false}; ///< number of actuators currently available
static UavcanNode *_instance;
static CyphalNode *_instance;
CanardHandle _canard_handle;
pthread_mutex_t _node_mutex;
@@ -178,26 +162,26 @@ private:
CanardTransferID _uavcan_node_heartbeat_transfer_id{0};
DEFINE_PARAMETERS(
(ParamInt<px4::params::UAVCAN_V1_ENABLE>) _param_uavcan_v1_enable,
(ParamInt<px4::params::UAVCAN_V1_ID>) _param_uavcan_v1_id,
(ParamInt<px4::params::UAVCAN_V1_BAUD>) _param_uavcan_v1_baud
(ParamInt<px4::params::CYPHAL_ENABLE>) _param_uavcan_v1_enable,
(ParamInt<px4::params::CYPHAL_ID>) _param_uavcan_v1_id,
(ParamInt<px4::params::CYPHAL_BAUD>) _param_uavcan_v1_baud
)
UavcanParamManager _param_manager;
#ifdef CONFIG_UAVCAN_V1_NODE_MANAGER
NodeManager _node_manager {_canard_instance, _param_manager};
#ifdef CONFIG_CYPHAL_NODE_MANAGER
NodeManager _node_manager {_canard_handle, _param_manager};
#endif
#ifdef CONFIG_UAVCAN_V1_NODE_CLIENT
#ifdef CONFIG_CYPHAL_NODE_CLIENT
NodeClient *_node_client {nullptr};
#endif
PublicationManager _pub_manager {_canard_instance, _param_manager};
SubscriptionManager _sub_manager {_canard_instance, _param_manager};
PublicationManager _pub_manager {_canard_handle, _param_manager};
SubscriptionManager _sub_manager {_canard_handle, _param_manager};
/// TODO: Integrate with PublicationManager
UavcanEscController _esc_controller {_canard_instance, _param_manager};
UavcanEscController _esc_controller {_canard_handle, _param_manager};
UavcanMixingInterface _mixing_output {_node_mutex, _esc_controller};
@@ -2,65 +2,65 @@
# For a description of the syntax of this configuration file,
# see the file kconfig-language.txt in the NuttX tools repository.
#
menuconfig DRIVERS_UAVCAN_V1
bool "UAVCANv1"
menuconfig DRIVERS_CYPHAL
bool "Cyphal"
default n
---help---
Enable support for UAVCANv1
Enable support for Cyphal
if DRIVERS_UAVCAN_V1
if DRIVERS_CYPHAL
choice
prompt "UAVCANv1 Mode"
prompt "Cyphal Mode"
config UAVCAN_V1_FMU
config CYPHAL_FMU
bool "Server (FMU)"
config UAVCAN_V1_CLIENT
config CYPHAL_CLIENT
bool "Client (Peripheral)"
endchoice
config UAVCAN_V1_NODE_MANAGER
config CYPHAL_NODE_MANAGER
bool "Node manager"
default y
depends on UAVCAN_V1_FMU
depends on CYPHAL_FMU
help
Implement UAVCAN v1 PNP server functionality and manages discovered nodes
Implement Cyphal PNP server functionality and manages discovered nodes
config UAVCAN_V1_NODE_CLIENT
config CYPHAL_NODE_CLIENT
bool "Node client"
default y
depends on UAVCAN_V1_CLIENT
depends on CYPHAL_CLIENT
help
Implement UAVCAN v1 PNP client functionality
Implement Cyphal PNP client functionality
config UAVCAN_V1_APP_DESCRIPTOR
config CYPHAL_APP_DESCRIPTOR
bool "UAVCAN v0 bootloader app descriptor"
default n
depends on UAVCAN_V1_CLIENT && DRIVERS_BOOTLOADERS
depends on CYPHAL_CLIENT && DRIVERS_BOOTLOADERS
help
When the board uses the UAVCANv0 bootloader functionality you need a AppImageDescriptor defined
menu "Publisher support"
config UAVCAN_V1_GNSS_PUBLISHER
config CYPHAL_GNSS_PUBLISHER
bool "GNSS Publisher"
default n
config UAVCAN_V1_ESC_CONTROLLER
config CYPHAL_ESC_CONTROLLER
bool "ESC Controller"
default n
config UAVCAN_V1_READINESS_PUBLISHER
config CYPHAL_READINESS_PUBLISHER
bool "Readiness Publisher"
default n
config UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER
config CYPHAL_UORB_ACTUATOR_OUTPUTS_PUBLISHER
bool "uORB actuator_outputs publisher"
default n
config UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER
config CYPHAL_UORB_SENSOR_GPS_PUBLISHER
bool "uORB sensor_gps publisher"
default n
@@ -68,36 +68,36 @@ if DRIVERS_UAVCAN_V1
menu "Subscriber support"
config UAVCAN_V1_ESC_SUBSCRIBER
config CYPHAL_ESC_SUBSCRIBER
bool "ESC Subscriber"
default n
config UAVCAN_V1_GNSS_SUBSCRIBER_0
config CYPHAL_GNSS_SUBSCRIBER_0
bool "GNSS Subscriber 0"
default n
config UAVCAN_V1_GNSS_SUBSCRIBER_1
config CYPHAL_GNSS_SUBSCRIBER_1
bool "GNSS Subscriber 1"
default n
config UAVCAN_V1_BMS_SUBSCRIBER
config CYPHAL_BMS_SUBSCRIBER
bool "BMS Subscriber"
default n
config UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER
config CYPHAL_UORB_SENSOR_GPS_SUBSCRIBER
bool "uORB sensor_gps Subscriber"
default n
endmenu
menu "Advertised Services"
config UAVCAN_V1_GETINFO_RESPONDER
config CYPHAL_GETINFO_RESPONDER
bool "GetInfo1.0 responder"
default y
help
Responds to uavcan.node.GetInfo.1.0 request sending over node information
See https://github.com/UAVCAN/public_regulated_data_types/blob/master/uavcan/node/430.GetInfo.1.0.uavcan for full response
config UAVCAN_V1_EXECUTECOMMAND_RESPONDER
config CYPHAL_EXECUTECOMMAND_RESPONDER
bool "ExecuteCommand1.0 responder"
default n
help
@@ -107,4 +107,4 @@ if DRIVERS_UAVCAN_V1
menu "Service invokers"
endmenu
endif #DRIVERS_UAVCAN_V1
endif #DRIVERS_CYPHAL
@@ -44,15 +44,15 @@
#include <crc64.h>
#include "NodeClient.hpp"
void NodeClient::callback(const CanardTransfer &receive)
void NodeClient::callback(const CanardRxTransfer &receive)
{
if (receive.remote_node_id != CANARD_NODE_ID_UNSET && _canard_instance.node_id == CANARD_NODE_ID_UNSET) {
if (receive.metadata.remote_node_id != CANARD_NODE_ID_UNSET && _canard_handle.node_id() == CANARD_NODE_ID_UNSET) {
int32_t allocated = CANARD_NODE_ID_UNSET;
px4_guid_t px4_guid;
board_get_px4_guid(px4_guid);
if (_canard_instance.mtu_bytes == CANARD_MTU_CAN_FD) {
if (_canard_handle.mtu() == CANARD_MTU_CAN_FD) {
uavcan_pnp_NodeIDAllocationData_2_0 msg;
size_t msg_size_in_bytes = receive.payload_size;
@@ -87,9 +87,9 @@ void NodeClient::callback(const CanardTransfer &receive)
return;
}
_canard_instance.node_id = allocated;
_canard_handle.set_node_id(allocated);
PX4_INFO("Allocated Node ID %d", _canard_instance.node_id);
PX4_INFO("Allocated Node ID %d", _canard_handle.node_id());
}
}
@@ -103,38 +103,39 @@ void NodeClient::update()
int32_t result;
// Allocation already done, nothing to do
if (_canard_instance.node_id != CANARD_NODE_ID_UNSET) {
if (_canard_handle.node_id() != CANARD_NODE_ID_UNSET) {
return;
}
if (_canard_instance.mtu_bytes == CANARD_MTU_CAN_FD) {
if (_canard_handle.mtu() == CANARD_MTU_CAN_FD) {
// NodeIDAllocationData message
uavcan_pnp_NodeIDAllocationData_2_0 node_id_alloc_msg;
uint8_t node_id_alloc_payload_buffer[PNP2_PAYLOAD_SIZE];
size_t payload_size = PNP2_PAYLOAD_SIZE;
px4_guid_t px4_guid;
board_get_px4_guid(px4_guid);
memcpy(node_id_alloc_msg.unique_id, px4_guid, sizeof(node_id_alloc_msg.unique_id));
//node_id_alloc_msg.node_id.value = preffered_node_id; //FIXME preffered ID PX4 Param
CanardTransfer transfer = {
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC, // Zero if transmission deadline is not limited.
const CanardTransferMetadata transfer_metadata = {
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = PNP2_PORT_ID, // This is the subject-ID.
.remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
.transfer_id = _node_id_alloc_transfer_id,
.payload_size = PNP2_PAYLOAD_SIZE,
.payload = &node_id_alloc_payload_buffer,
};
result = uavcan_pnp_NodeIDAllocationData_2_0_serialize_(&node_id_alloc_msg, (uint8_t *)&node_id_alloc_payload_buffer,
&transfer.payload_size);
&payload_size);
if (result == 0) {
// set the data ready in the buffer and chop if needed
++_node_id_alloc_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
canardTxPush(&_canard_instance, &transfer);
_canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
&transfer_metadata,
payload_size,
&node_id_alloc_payload_buffer);
}
} else {
@@ -142,29 +143,30 @@ void NodeClient::update()
uavcan_pnp_NodeIDAllocationData_1_0 node_id_alloc_msg;
uavcan_pnp_NodeIDAllocationData_1_0_initialize_(&node_id_alloc_msg);
uint8_t node_id_alloc_payload_buffer[PNP1_PAYLOAD_SIZE];
size_t payload_size = PNP1_PAYLOAD_SIZE;
px4_guid_t px4_guid;
board_get_px4_guid(px4_guid);
node_id_alloc_msg.unique_id_hash = (crc64(px4_guid, PNP_UNIQUE_ID_SIZE) & 0xFFFFFFFFFFFF);
CanardTransfer transfer = {
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC, // Zero if transmission deadline is not limited.
const CanardTransferMetadata transfer_metadata = {
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = PNP1_PORT_ID, // This is the subject-ID.
.remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
.transfer_id = _node_id_alloc_transfer_id,
.payload_size = PNP1_PAYLOAD_SIZE,
.payload = &node_id_alloc_payload_buffer,
};
result = uavcan_pnp_NodeIDAllocationData_1_0_serialize_(&node_id_alloc_msg, (uint8_t *)&node_id_alloc_payload_buffer,
&transfer.payload_size);
&payload_size);
if (result == 0) {
// set the data ready in the buffer and chop if needed
++_node_id_alloc_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
canardTxPush(&_canard_instance, &transfer);
_canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
&transfer_metadata,
payload_size,
&node_id_alloc_payload_buffer);
}
}
@@ -62,30 +62,30 @@
class NodeClient : public UavcanBaseSubscriber
{
public:
NodeClient(CanardInstance &ins, UavcanParamManager &pmgr) : UavcanBaseSubscriber(ins, "NodeIDAllocationData", 0),
_canard_instance(ins) { };
NodeClient(CanardHandle &handle, UavcanParamManager &pmgr) : UavcanBaseSubscriber(handle, "", "NodeIDAllocationData",
0),
_canard_handle(handle) { };
void subscribe() override
{
canardRxSubscribe(&_canard_instance,
CanardTransferKindMessage,
(_canard_instance.mtu_bytes == CANARD_MTU_CAN_FD ? PNP2_PORT_ID : PNP1_PORT_ID), // The fixed Subject-ID
(_canard_instance.mtu_bytes == CANARD_MTU_CAN_FD ? PNP2_PAYLOAD_SIZE : PNP1_PAYLOAD_SIZE),
CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC,
&_subj_sub._canard_sub);
_canard_handle.RxSubscribe(CanardTransferKindMessage,
(_canard_handle.mtu() == CANARD_MTU_CAN_FD ? PNP2_PORT_ID : PNP1_PORT_ID), // The fixed Subject-ID
(_canard_handle.mtu() == CANARD_MTU_CAN_FD ? PNP2_PAYLOAD_SIZE : PNP1_PAYLOAD_SIZE),
CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC,
&_subj_sub._canard_sub);
}
bool HandleNodeIDRequest(uavcan_pnp_NodeIDAllocationData_1_0 &msg);
bool HandleNodeIDRequest(uavcan_pnp_NodeIDAllocationData_2_0 &msg);
void callback(const CanardTransfer &receive); // NodeIDAllocation callback
void callback(const CanardRxTransfer &receive); // NodeIDAllocation callback
void update();
private:
CanardInstance &_canard_instance;
CanardHandle &_canard_handle;
CanardTransferID _node_id_alloc_transfer_id{0};
hrt_abstime _nodealloc_request_last{0};
@@ -43,9 +43,9 @@
#include "NodeManager.hpp"
void NodeManager::callback(const CanardTransfer &receive)
void NodeManager::callback(const CanardRxTransfer &receive)
{
if (_canard_instance.mtu_bytes == CANARD_MTU_CAN_FD) {
if (_canard_handle.mtu() == CANARD_MTU_CAN_FD) {
uavcan_pnp_NodeIDAllocationData_2_0 node_id_alloc_msg {};
size_t msg_size_in_bytes = receive.payload_size;
uavcan_pnp_NodeIDAllocationData_2_0_deserialize_(&node_id_alloc_msg, (const uint8_t *)receive.payload,
@@ -73,7 +73,7 @@ bool NodeManager::HandleNodeIDRequest(uavcan_pnp_NodeIDAllocationData_1_0 &msg)
/* Search for an available NodeID to assign */
for (i = 1; i < sizeof(nodeid_registry) / sizeof(nodeid_registry[0]); i++) {
if (i == _canard_instance.node_id) {
if (i == _canard_handle.node_id()) {
continue; // Don't give our NodeID to a node
} else if (nodeid_registry[i].node_id == 0) { // Unused
@@ -96,24 +96,25 @@ bool NodeManager::HandleNodeIDRequest(uavcan_pnp_NodeIDAllocationData_1_0 &msg)
PX4_INFO("Received NodeID allocation request assigning %i", msg.allocated_node_id.elements[0].value);
uint8_t node_id_alloc_payload_buffer[uavcan_pnp_NodeIDAllocationData_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_];
size_t payload_size = uavcan_pnp_NodeIDAllocationData_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_;
CanardTransfer transfer = {
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
const CanardTransferMetadata transfer_metadata = {
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = uavcan_pnp_NodeIDAllocationData_1_0_FIXED_PORT_ID_, // This is the subject-ID.
.remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
.transfer_id = _uavcan_pnp_nodeidallocation_v1_transfer_id,
.payload_size = uavcan_pnp_NodeIDAllocationData_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_,
.payload = &node_id_alloc_payload_buffer,
};
int result = uavcan_pnp_NodeIDAllocationData_1_0_serialize_(&msg, node_id_alloc_payload_buffer, &transfer.payload_size);
int result = uavcan_pnp_NodeIDAllocationData_1_0_serialize_(&msg, node_id_alloc_payload_buffer, &payload_size);
if (result == 0) {
// set the data ready in the buffer and chop if needed
++_uavcan_pnp_nodeidallocation_v1_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
result = canardTxPush(&_canard_instance, &transfer);
_canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
&transfer_metadata,
payload_size,
&node_id_alloc_payload_buffer);
}
_register_request_last = hrt_absolute_time();
@@ -132,7 +133,7 @@ bool NodeManager::HandleNodeIDRequest(uavcan_pnp_NodeIDAllocationData_2_0 &msg)
}
void NodeManager::HandleListResponse(const CanardTransfer &receive)
void NodeManager::HandleListResponse(const CanardRxTransfer &receive)
{
uavcan_register_List_Response_1_0 msg;
@@ -142,21 +143,21 @@ void NodeManager::HandleListResponse(const CanardTransfer &receive)
if (msg.name.name.count == 0) {
// Index doesn't exist, we've parsed through all registers
for (uint32_t i = 0; i < sizeof(nodeid_registry) / sizeof(nodeid_registry[0]); i++) {
if (nodeid_registry[i].node_id == receive.remote_node_id) {
if (nodeid_registry[i].node_id == receive.metadata.remote_node_id) {
nodeid_registry[i].register_setup = true; // Don't update anymore
}
}
} else {
for (uint32_t i = 0; i < sizeof(nodeid_registry) / sizeof(nodeid_registry[0]); i++) {
if (nodeid_registry[i].node_id == receive.remote_node_id) {
if (nodeid_registry[i].node_id == receive.metadata.remote_node_id) {
nodeid_registry[i].register_index++; // Increment index counter for next update()
nodeid_registry[i].register_setup = false;
nodeid_registry[i].retry_count = 0;
}
}
if (_access_request.setPortId(receive.remote_node_id, msg.name, NULL)) { //FIXME confirm handler
if (_access_request.setPortId(receive.metadata.remote_node_id, msg.name, NULL)) { //FIXME confirm handler
PX4_INFO("Set portID succesfull");
} else {
@@ -70,37 +70,37 @@ typedef struct {
class NodeManager : public UavcanBaseSubscriber, public UavcanServiceRequestInterface
{
public:
NodeManager(CanardInstance &ins, UavcanParamManager &pmgr) : UavcanBaseSubscriber(ins, "", "NodeIDAllocationData", 0),
_canard_instance(ins), _access_request(ins, pmgr), _list_request(ins) { };
NodeManager(CanardHandle &handle, UavcanParamManager &pmgr) : UavcanBaseSubscriber(handle, "", "NodeIDAllocationData",
0),
_canard_handle(handle), _access_request(handle, pmgr), _list_request(handle) { };
void subscribe() override
{
_access_request.subscribe();
_list_request.subscribe();
canardRxSubscribe(&_canard_instance,
CanardTransferKindMessage,
(_canard_instance.mtu_bytes == CANARD_MTU_CAN_FD ? PNP2_PORT_ID : PNP1_PORT_ID), // The fixed Subject-ID
(_canard_instance.mtu_bytes == CANARD_MTU_CAN_FD ? PNP2_PAYLOAD_SIZE : PNP1_PAYLOAD_SIZE),
CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC,
&_subj_sub._canard_sub);
_canard_handle.RxSubscribe(CanardTransferKindMessage,
(_canard_handle.mtu() == CANARD_MTU_CAN_FD ? PNP2_PORT_ID : PNP1_PORT_ID), // The fixed Subject-ID
(_canard_handle.mtu() == CANARD_MTU_CAN_FD ? PNP2_PAYLOAD_SIZE : PNP1_PAYLOAD_SIZE),
CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC,
&_subj_sub._canard_sub);
}
bool HandleNodeIDRequest(uavcan_pnp_NodeIDAllocationData_1_0 &msg);
bool HandleNodeIDRequest(uavcan_pnp_NodeIDAllocationData_2_0 &msg);
void response_callback(const CanardTransfer &receive) override
void response_callback(const CanardRxTransfer &receive) override
{
HandleListResponse(receive);
}
void callback(const CanardTransfer &receive); // NodeIDAllocation callback
void callback(const CanardRxTransfer &receive); // NodeIDAllocation callback
void HandleListResponse(const CanardTransfer &receive);
void HandleListResponse(const CanardRxTransfer &receive);
void update();
private:
CanardInstance &_canard_instance;
CanardHandle &_canard_handle;
CanardTransferID _uavcan_pnp_nodeidallocation_v1_transfer_id{0};
UavcanNodeEntry nodeid_registry[16] {0}; //TODO configurable or just rewrite
@@ -56,10 +56,11 @@ void PublicationManager::updateDynamicPublications()
for (auto &dynpub : _dynpublishers) {
// Check if subscriber has already been created
const char *subj_name = dynpub->getSubjectName();
char full_subj_name[200];
snprintf(full_subj_name, sizeof(full_subj_name), "%s%s", dynpub->getPrefixName(), dynpub->getSubjectName());
const uint8_t instance = dynpub->getInstance();
if (strcmp(subj_name, sub.subject_name) == 0 && instance == sub.instance) {
if (strcmp(full_subj_name, sub.subject_name) == 0 && instance == sub.instance) {
found_publisher = true;
break;
}
@@ -77,7 +78,7 @@ void PublicationManager::updateDynamicPublications()
uint16_t port_id = value.natural16.value.elements[0];
if (port_id <= CANARD_PORT_ID_MAX) { // PortID is set, create a subscriber
UavcanPublisher *dynpub = sub.create_pub(_canard_instance, _param_manager);
UavcanPublisher *dynpub = sub.create_pub(_canard_handle, _param_manager);
if (dynpub == nullptr) {
PX4_ERR("Out of memory");
@@ -44,33 +44,33 @@
#include <px4_platform_common/px4_config.h>
#ifndef CONFIG_UAVCAN_V1_GNSS_PUBLISHER
#define CONFIG_UAVCAN_V1_GNSS_PUBLISHER 0
#ifndef CONFIG_CYPHAL_GNSS_PUBLISHER
#define CONFIG_CYPHAL_GNSS_PUBLISHER 0
#endif
#ifndef CONFIG_UAVCAN_V1_ESC_CONTROLLER
#define CONFIG_UAVCAN_V1_ESC_CONTROLLER 0
#ifndef CONFIG_CYPHAL_ESC_CONTROLLER
#define CONFIG_CYPHAL_ESC_CONTROLLER 0
#endif
#ifndef CONFIG_UAVCAN_V1_READINESS_PUBLISHER
#define CONFIG_UAVCAN_V1_READINESS_PUBLISHER 0
#ifndef CONFIG_CYPHAL_READINESS_PUBLISHER
#define CONFIG_CYPHAL_READINESS_PUBLISHER 0
#endif
#ifndef CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER
#define CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER 0
#ifndef CONFIG_CYPHAL_UORB_ACTUATOR_OUTPUTS_PUBLISHER
#define CONFIG_CYPHAL_UORB_ACTUATOR_OUTPUTS_PUBLISHER 0
#endif
#ifndef CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER
#define CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER 0
#ifndef CONFIG_CYPHAL_UORB_SENSOR_GPS_PUBLISHER
#define CONFIG_CYPHAL_UORB_SENSOR_GPS_PUBLISHER 0
#endif
/* Preprocessor calculation of publisher count */
#define UAVCAN_PUB_COUNT CONFIG_UAVCAN_V1_GNSS_PUBLISHER + \
CONFIG_UAVCAN_V1_ESC_CONTROLLER + \
CONFIG_UAVCAN_V1_READINESS_PUBLISHER + \
CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER + \
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER
#define UAVCAN_PUB_COUNT CONFIG_CYPHAL_GNSS_PUBLISHER + \
CONFIG_CYPHAL_ESC_CONTROLLER + \
CONFIG_CYPHAL_READINESS_PUBLISHER + \
CONFIG_CYPHAL_UORB_ACTUATOR_OUTPUTS_PUBLISHER + \
CONFIG_CYPHAL_UORB_SENSOR_GPS_PUBLISHER
#include <px4_platform_common/defines.h>
#include <drivers/drv_hrt.h>
@@ -81,12 +81,12 @@
#include <uORB/topics/sensor_gps.h>
#include "Actuators/EscClient.hpp"
#include "Publishers/DS-015/Readiness.hpp"
#include "Publishers/DS-015/Gnss.hpp"
#include "Publishers/udral/Readiness.hpp"
#include "Publishers/udral/Gnss.hpp"
#include "Publishers/uORB/uorb_publisher.hpp"
typedef struct {
UavcanPublisher *(*create_pub)(CanardInstance &ins, UavcanParamManager &pmgr) {};
UavcanPublisher *(*create_pub)(CanardHandle &handle, UavcanParamManager &pmgr) {};
const char *subject_name;
const uint8_t instance;
} UavcanDynPubBinder;
@@ -94,7 +94,7 @@ typedef struct {
class PublicationManager
{
public:
PublicationManager(CanardInstance &ins, UavcanParamManager &pmgr) : _canard_instance(ins), _param_manager(pmgr) {}
PublicationManager(CanardHandle &handle, UavcanParamManager &pmgr) : _canard_handle(handle), _param_manager(pmgr) {}
~PublicationManager();
void update();
@@ -104,57 +104,57 @@ public:
private:
void updateDynamicPublications();
CanardInstance &_canard_instance;
CanardHandle &_canard_handle;
UavcanParamManager &_param_manager;
List<UavcanPublisher *> _dynpublishers;
const UavcanDynPubBinder _uavcan_pubs[UAVCAN_PUB_COUNT] {
#if CONFIG_UAVCAN_V1_GNSS_PUBLISHER
#if CONFIG_CYPHAL_GNSS_PUBLISHER
{
[](CanardInstance & ins, UavcanParamManager & pmgr) -> UavcanPublisher *
[](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanPublisher *
{
return new UavcanGnssPublisher(ins, pmgr, 0);
return new UavcanGnssPublisher(handle, pmgr, 0);
},
"gps",
0
},
#endif
#if CONFIG_UAVCAN_V1_ESC_CONTROLLER
#if CONFIG_CYPHAL_ESC_CONTROLLER
{
[](CanardInstance & ins, UavcanParamManager & pmgr) -> UavcanPublisher *
[](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanPublisher *
{
return new UavcanEscController(ins, pmgr);
return new UavcanEscController(handle, pmgr);
},
"esc",
0
},
#endif
#if CONFIG_UAVCAN_V1_READINESS_PUBLISHER
#if CONFIG_CYPHAL_READINESS_PUBLISHER
{
[](CanardInstance & ins, UavcanParamManager & pmgr) -> UavcanPublisher *
[](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanPublisher *
{
return new UavcanReadinessPublisher(ins, pmgr, 0);
return new UavcanReadinessPublisher(handle, pmgr, 0);
},
"readiness",
0
},
#endif
#if CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER
#if CONFIG_CYPHAL_UORB_ACTUATOR_OUTPUTS_PUBLISHER
{
[](CanardInstance & ins, UavcanParamManager & pmgr) -> UavcanPublisher *
[](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanPublisher *
{
return new uORB_over_UAVCAN_Publisher<actuator_outputs_s>(ins, pmgr, ORB_ID(actuator_outputs));
return new uORB_over_UAVCAN_Publisher<actuator_outputs_s>(handle, pmgr, ORB_ID(actuator_outputs));
},
"uorb.actuator_outputs",
0
},
#endif
#if CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER
#if CONFIG_CYPHAL_UORB_SENSOR_GPS_PUBLISHER
{
[](CanardInstance & ins, UavcanParamManager & pmgr) -> UavcanPublisher *
[](CanardHandle & handle, UavcanParamManager & pmgr) -> UavcanPublisher *
{
return new uORB_over_UAVCAN_Publisher<sensor_gps_s>(ins, pmgr, ORB_ID(sensor_gps));
return new uORB_over_UAVCAN_Publisher<sensor_gps_s>(handle, pmgr, ORB_ID(sensor_gps));
},
"uorb.sensor_gps",
0

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