mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_BoardConfig: wait for UAVCAN initialization complete signal
This commit is contained in:
parent
503e196546
commit
d2b6eb7700
@ -99,6 +99,12 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 && !defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
extern "C" int uavcan_main(int argc, const char *argv[]);
|
||||
|
||||
#define _UAVCAN_IOCBASE (0x4000) // IOCTL base for module UAVCAN
|
||||
#define _UAVCAN_IOC(_n) (_IOC(_UAVCAN_IOCBASE, _n))
|
||||
|
||||
#define UAVCAN_IOCG_NODEID_INPROGRESS _UAVCAN_IOC(1) // query if node identification is in progress
|
||||
|
||||
#endif
|
||||
|
||||
void AP_BoardConfig::init()
|
||||
@ -159,10 +165,18 @@ void AP_BoardConfig::init()
|
||||
if (ret != 0) {
|
||||
hal.console->printf("UAVCAN: failed to start servers\n");
|
||||
} else {
|
||||
hal.console->printf("UAVCAN: servers started\n");
|
||||
// give some time for CAN bus initialisation
|
||||
fd = open("/dev/uavcan/esc", 0); // design flaw of uavcan driver, this should be /dev/uavcan/node one day
|
||||
if (fd == -1) {
|
||||
AP_HAL::panic("Configuration invalid - unable to open /dev/uavcan/esc");
|
||||
}
|
||||
|
||||
// delay startup, UAVCAN still discovering nodes
|
||||
while (ioctl(fd, UAVCAN_IOCG_NODEID_INPROGRESS,0) == OK) {
|
||||
hal.scheduler->delay(500);
|
||||
}
|
||||
hal.console->printf("UAVCAN: node discovery complete\n");
|
||||
close(fd);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user