From 6a413babe081da03eeb6ef47074eb9fbccc5593f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 21 Oct 2019 09:11:04 +1100 Subject: [PATCH] AP_Periph: pat watchdog in param getset --- Tools/AP_Periph/can.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index d272d8dbcc..572c043092 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -42,6 +42,7 @@ #include #include #include +#include #include #include @@ -145,6 +146,9 @@ static void handle_get_node_info(CanardInstance* ins, */ static void handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer) { + // param fetch all can take a long time, so pat watchdog + stm32_watchdog_pat(); + uavcan_protocol_param_GetSetRequest req; uint8_t arraybuf[UAVCAN_PROTOCOL_PARAM_GETSET_REQUEST_NAME_MAX_LENGTH]; uint8_t *arraybuf_ptr = arraybuf;