@Moderator , the board is currently operational somehow. I made adjustments to the code, setting PD15 to a high level and modifying the parameters of UAVCAN_SUB_BAT to 1 and UAVCAN_ENABLE to 2 or 3, following the guidelines on this page (https://docs.px4.io/v1.12/zh/uavcan/pomegranate_systems_pm.html). Despite these modifications, I am still unable to retrieve battery information. I will also explore the PX4 forum for potential solutions. However, if you have additional suggestions, please feel free to share. Thank you.
diff --git a/boards/modalai/fc-v2/src/board_config.h b/boards/modalai/fc-v2/src/board_config.h
index 987f692b22..e7a7c83ef7 100644
--- a/boards/modalai/fc-v2/src/board_config.h
+++ b/boards/modalai/fc-v2/src/board_config.h
@@ -213,6 +213,7 @@
/* Spare GPIO */
#define CAN1_SILENT /* PD15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15)
+#define CAN1_SILENT_PULL_HIGH() px4_arch_gpiowrite(CAN1_SILENT, 1)
/* For primary/backup signaling with VOXL, 2 pins on J4 are exposed */
// GPIO_VOXL_STATUS_OUT/ GPIO_VOXL_STATUS_IN are for v1 Spare MSS Communications Interface and J4 tests
diff --git a/boards/modalai/fc-v2/src/init.c b/boards/modalai/fc-v2/src/init.c
index dbc6ec4637..55ad6aab6c 100644
--- a/boards/modalai/fc-v2/src/init.c
+++ b/boards/modalai/fc-v2/src/init.c
@@ -211,6 +211,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
/* Power on Interfaces */
board_spi_reset(10, 0xffff);
VDD_3V3_SPEKTRUM_POWER_EN(true);
+ CAN1_SILENT_PULL_HIGH();
nsh> uavcan status
Pool allocator status:
Capacity hard/soft: 500/250 blocks
Reserved: 6 blocks
Allocated: 6 blocks
UAVCAN node status:
Internal failures: 0
Transfer errors: 0
RX transfers: 0
TX transfers: 1079
CAN1 status:
HW errors: 310
IO errors: 310
RX frames: 2224
TX frames: 1296
ESC outputs:
INFO [mixer_module] Param prefix: UAVCAN_EC
control latency: 0 events, 0us elapsed, 0.00us avg, min 0us max 0us 0.000us rms
Channel Configuration:
Channel 0: func: 0, value: 0, failsafe: 65535, disarmed: 65535, min: 1, max: 8191
Channel 1: func: 0, value: 0, failsafe: 65535, disarmed: 65535, min: 1, max: 8191
Channel 2: func: 0, value: 0, failsafe: 65535, disarmed: 65535, min: 1, max: 8191
Channel 3: func: 0, value: 0, failsafe: 65535, disarmed: 65535, min: 1, max: 8191
Channel 4: func: 0, value: 0, failsafe: 65535, disarmed: 65535, min: 1, max: 8191
Channel 5: func: 0, value: 0, failsafe: 65535, disarmed: 65535, min: 1, max: 8191
Channel 6: func: 0, value: 0, failsafe: 65535, disarmed: 65535, min: 1, max: 8191
Channel 7: func: 0, value: 0, failsafe: 65535, disarmed: 65535, min: 1, max: 8191
Servo outputs:
INFO [mixer_module] Param prefix: UAVCAN_SV
control latency: 0 events, 0us elapsed, 0.00us avg, min 0us max 0us 0.000us rms
Channel Configuration:
Channel 0: func: 0, value: 0, failsafe: 500, disarmed: 500, min: 0, max: 1000
Channel 1: func: 0, value: 0, failsafe: 500, disarmed: 500, min: 0, max: 1000
Channel 2: func: 0, value: 0, failsafe: 500, disarmed: 500, min: 0, max: 1000
Channel 3: func: 0, value: 0, failsafe: 500, disarmed: 500, min: 0, max: 1000
Channel 4: func: 0, value: 0, failsafe: 500, disarmed: 500, min: 0, max: 1000
Channel 5: func: 0, value: 0, failsafe: 500, disarmed: 500, min: 0, max: 1000
Channel 6: func: 0, value: 0, failsafe: 500, disarmed: 500, min: 0, max: 1000
Channel 7: func: 0, value: 0, failsafe: 500, disarmed: 500, min: 0, max: 1000
Sensor 'battery':
name: uavcan_battery
Sensor 'mag':
name: uavcan_mag
Online nodes (Node ID, Health, Mode):
uavcan: cycle time: 25877 events, 363400us elapsed, 14.04us avg, min 6us max 587us 24.085us rms
uavcan: cycle interval: 25877 events, 2747.60us avg, min 15us max 3734us 716.959us rms