mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_UAVCAN: increase message timeout to 2ms
this reduces the number of msg timeouts
This commit is contained in:
parent
b8ae43c30b
commit
438a7dd79a
@ -84,7 +84,7 @@ const AP_Param::GroupInfo AP_UAVCAN::var_info[] = {
|
||||
|
||||
// this is the timeout in milliseconds for periodic message types. We
|
||||
// set this to 1 to minimise resend of stale msgs
|
||||
#define CAN_PERIODIC_TX_TIMEOUT_MS 1
|
||||
#define CAN_PERIODIC_TX_TIMEOUT_MS 2
|
||||
|
||||
static void gnss_fix_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix>& msg, uint8_t mgr)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user