mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_DroneCAN: set priority and timeout for RGB LEDs
This commit is contained in:
parent
e5dda42056
commit
93c1674e1f
@ -309,6 +309,9 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters)
|
|||||||
node_status.set_priority(CANARD_TRANSFER_PRIORITY_LOWEST);
|
node_status.set_priority(CANARD_TRANSFER_PRIORITY_LOWEST);
|
||||||
node_status.set_timeout_ms(1000);
|
node_status.set_timeout_ms(1000);
|
||||||
|
|
||||||
|
rgb_led.set_timeout_ms(20);
|
||||||
|
rgb_led.set_priority(CANARD_TRANSFER_PRIORITY_LOW);
|
||||||
|
|
||||||
node_info_server.set_timeout_ms(20);
|
node_info_server.set_timeout_ms(20);
|
||||||
|
|
||||||
// setup node status
|
// setup node status
|
||||||
|
Loading…
Reference in New Issue
Block a user